commit e61d8f2175b4678668f74e2896e3bce58aad6b72 Author: Rdzleo Date: Fri Apr 17 15:45:49 2026 +0800 AI桌面机器人-摄像头版项目初始化 diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..a1b5d8e --- /dev/null +++ b/.gitignore @@ -0,0 +1,19 @@ +tmp/ +components/ +managed_components/ +build/ +.vscode/ +.devcontainer/ +sdkconfig.old +sdkconfig +dependencies.lock +.env +releases/ +main/assets/lang_config.h +main/mmap_generate_emoji.h +.DS_Store +.cache +*.pyc +*.bin +mmap_generate_*.h +.clangd diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100755 index 0000000..9f147d2 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,14 @@ +# For more information about build system see +# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html +# The following five lines of boilerplate have to be in your project's +# CMakeLists in this exact order for cmake to work correctly +cmake_minimum_required(VERSION 3.16) + +set(PROJECT_VER "2.0.5") + +# Add this line to disable the specific warning +add_compile_options(-Wno-missing-field-initializers) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +project(xiaozhi) + diff --git a/Coglet项目分析与开发指南.md b/Coglet项目分析与开发指南.md new file mode 100644 index 0000000..64c15f8 --- /dev/null +++ b/Coglet项目分析与开发指南.md @@ -0,0 +1,602 @@ +# Coglet 项目分析与开发指南 + +## 一、项目简介 + +**Coglet** 是 YouTube 创作者 Will Cogley(原 Nilheim Mechatronics)开发的 **DIY 桌面 AI 伴侣机器人**,目前在 Kickstarter 众筹中。项目包含 3D 打印外壳、PCB 电路板和双 MCU 软件系统。 + +### 系统架构 + +采用**双 MCU 架构**,三个核心模块通过 UART 串联: + +``` +ESP32-S3 ←── UART 115200 ──→ RP2040 (Pico) ←── UART 921600 ──→ Grove Vision AI V2 + (AI/语音/网络) (舵机/动画) (摄像头/人脸检测) +``` + +| 芯片 | 职责 | +|------|------| +| **ESP32-S3** | AI 对话、语音识别/合成、WiFi 网络、MCP 协议(基于小智 XiaoZhi 固件) | +| **RP2040 (Raspberry Pi Pico)** | 9 个舵机控制、动画表情、人脸追踪(MicroPython) | +| **Grove Vision AI V2** | 摄像头人脸检测 | + +### ESP32 固件核心功能 + +- 连接方式:WiFi / ML307 Cat.1 4G +- 语音交互:流式 ASR + LLM(Qwen/DeepSeek)+ TTS +- 离线唤醒:ESP-SR 本地语音唤醒 +- 通信协议:WebSocket 或 MQTT+UDP +- 音频编码:OPUS +- 显示:OLED/LCD + 表情动画 +- 多语言:中文/英文/日文 +- MCP 协议:设备端 MCP(控制扬声器、LED、舵机、GPIO)+ 云端 MCP(智能家居) + +### RP2040 控制的舵机(共 9 个) + +| 舵机代号 | 功能 | +|---------|------| +| EYL / EYR | 左右眼水平转动 | +| PIT | 头部俯仰 | +| YAW | 头部偏航 | +| MOU | 嘴巴开合 | +| LID | 眼睑眨眼 | +| 其他 | 耳朵舵机等 | + +### RP2040 状态机 + +`idle` → `speaking` → `listening` → `thinking` → `happy` → `neutral` → `calibration` + +--- + +## 二、GitHub 仓库总览 + +### 核心仓库 + +| 仓库 | 地址 | Stars | 说明 | +|------|------|-------|------| +| **Coglet 主仓库** | https://github.com/will-cogley/Coglet | 135 | 3D 打印件、PCB 原理图、文档 | +| **CogletESP 固件** | https://github.com/will-cogley/CogletESP | 5 | ESP32 固件 + RP2040 代码(fork 自小智) | + +### 相关参考仓库 + +| 仓库 | 地址 | 说明 | +|------|------|------| +| 小智上游原版 | https://github.com/78/xiaozhi-esp32 | CogletESP 的上游项目 | +| EyeMech_Epsilon | https://github.com/will-cogley/EyeMech_Epsilon | Coglet 眼球机构的技术前身,RP2040 + MicroPython | + +### CogletESP 分支列表 + +| 分支名 | Commits | 说明 | +|--------|---------|------| +| `main` | 789 | 上游同步的主分支 | +| **`CogletESP`** | 758 | **Coglet 专用分支(无 ESP32 摄像头版本,保留 LCD 显示)** | +| **`camera-version`** | 755 | **ESP32 OV3660 摄像头版本(需 PCB 飞线,禁用 LCD)** | +| `esp32_camera` | - | ESP32 摄像头分支 | +| `v1` | 669 | v1 稳定版 | +| `bed-operator` | - | 功能分支 | +| `fix_resampler` | - | 重采样器修复 | +| `fix_rndis` | - | RNDIS 修复 | +| `listening_wakeword` | - | 唤醒词监听 | +| `nt26_board` | - | NT26 开发板适配 | + +### CogletESP 分支 vs camera-version 分支(关键区别) + +> **重要区分**:这里的"摄像头"指 **ESP32-S3 上直连的 OV3660 DVP 摄像头**(小智 AI 视觉功能),**不是** Grove Vision AI V2。Grove Vision AI V2 是独立模块接在 RP2040 上,两个分支都支持它。 + +两个分支仅 **2 个文件**不同,都在 `main/boards/bread-compact-wifi-s3cam/` 目录下: + +| 对比项 | `CogletESP` 分支 | `camera-version` 分支 | +|--------|------------------|----------------------| +| ESP32 摄像头(OV3660) | 默认引脚,与 PSRAM 冲突 | 飞线后的新引脚映射 | +| LCD 显示 | 正常支持 | **禁用**(引脚被摄像头占用,用 DummyDisplay 替代) | +| PCB 改动 | 无需飞线 | **需要 3 根飞线**(35→14, 36→41, 37→42) | +| 摄像头画面 | - | 设置 HMirror + VFlip 翻转 | +| JTAG 引脚(GPIO 39-42) | 默认用途 | 释放给摄像头使用 | +| Grove Vision AI V2 | 支持 | 支持 | + +#### GPIO 引脚映射差异(部分关键引脚) + +| 功能 | `CogletESP` 分支 | `camera-version` 分支 | +|------|------------------|----------------------| +| MIC_WS | GPIO 1 | GPIO 4 | +| MIC_SCK | GPIO 2 | GPIO 5 | +| MIC_DIN | GPIO 42 | GPIO 6 | +| SPK_DOUT | GPIO 39 | GPIO 7 | +| SPK_BCLK | GPIO 40 | GPIO 15 | +| SPK_LRCK | GPIO 41 | GPIO 16 | +| LED | GPIO 48 | GPIO 3 | +| CAMERA D7 | GPIO 16 | GPIO 14(飞线 35→14) | +| CAMERA VSYNC | GPIO 6 | GPIO 41(飞线 36→41) | +| CAMERA HREF | GPIO 7 | GPIO 42(飞线 37→42) | + +#### 如何选择分支? + +- **带 ESP32 OV3660 摄像头** → 用 `camera-version` 分支 + PCB 做 3 根飞线,但**没有 LCD 屏** +- **不带 ESP32 摄像头 / 想保留 LCD 屏** → 用 `CogletESP` 分支 +- **仅使用 Grove Vision AI V2 人脸追踪** → 两个分支都可以,这是 RP2040 端的功能,与 ESP32 分支无关 + +### Coglet 主仓库目录结构 + +``` +Coglet/ +├── 3D Printing Files/ +│ └── CogletB34Parts.3mf # 3D 打印零件 +├── PCB/ +│ ├── CogNogV1_0.pdf # 原理图 PDF +│ └── CogletESP_2026-02-24.epro # EasyEDA 工程文件 +├── CogletESP/ # Git 子模块 → CogletESP 仓库 +├── Translated Docs for XiaoZhi AI/ # 14 份小智文档英文翻译 +│ ├── 固件烧录指南 +│ ├── WiFi 配置 +│ ├── 面包板接线 +│ ├── ESP-IDF 开发环境搭建 +│ └── 摄像头接线 ... +└── README.md +``` + +### 已知 PCB 问题(CogNog V1.0) + +- USB-C 接口过紧 +- **摄像头引脚与 PSRAM 冲突**(GPIO 35/36/37 被 PSRAM Octal SPI 占用,详见下方飞线说明) +- 体积电容不足 +- 摄像头画面水平翻转(camera-version 分支已通过 `SetHMirror(true)` 修正) + +### 翻译文档索引(Translated Docs for XiaoZhi AI) + +主仓库中 `Translated Docs for XiaoZhi AI/` 包含 13 份小智文档英文翻译,其中与搭建相关的: + +| 文件 | 内容 | +|------|------| +| **DIY Breadboard for Xiaozhi AI...** | 完整硬件清单和接线教程(最详细,18MB) | +| **[Latest] Wiring Tutorial...Camera** | **带摄像头的最新接线教程** | +| Setting up ESP IDF 5.5.2... | ESP-IDF 开发环境搭建(Windows) | +| Flash Tool_Web Terminal... | 网页烧录工具(无需 IDF 环境) | +| Configure Device Wi-Fi... | WiFi 配网和设备添加 | +| Steps for Wake Word Change... | 唤醒词修改 | + +--- + +## 三、项目状态 + +- **活跃度**:积极开发中(最后更新 2026 年 3 月) +- **成熟度**:早期阶段 / 工作进行中 + - Releases 页面为空,**无预编译固件** + - PCB 存在多个已知问题 + - 没有专用的 Coglet 板级配置(使用通用 bread-compact 系列) +- **众筹**:Kickstarter 进行中 +- **社区**:Discord + QQ 群 + +--- + +## 四、摄像头版本完整搭建流程(camera-version) + +> 你使用的是**带摄像头**的版本,以下是从零到运行的完整操作流程。 + +### 4.1 为什么需要飞线? + +**这是 CogNog V1.0 PCB 的设计缺陷,不是故意的设计。** + +ESP32-S3 的 PSRAM 使用 Octal SPI 接口,占用了 GPIO 35/36/37。但 V1.0 PCB 把摄像头的三个信号线(D7、VSYNC、HREF)也接到了这三个引脚上。当摄像头和 PSRAM 同时工作时,引脚冲突导致摄像头无法使用。 + +**所有使用 CogNog V1.0 PCB + 摄像头的用户都必须飞线。** 目前只有 V1.0 版本的 PCB。 + +### 4.2 硬件准备清单 + +| 部件 | 说明 | +|------|------| +| CogNog V1.0 PCB | 需要飞线修改 | +| ESP32-S3 模组 | 带 PSRAM(如 N16R8) | +| OV3660 摄像头模组 | DVP 接口 + 排线 + 转接板 | +| Grove Vision AI V2 | 人脸追踪模块 + 15pin 排线适配器 | +| INMP441 麦克风 | I2S 数字麦克风 | +| 扬声器 | I2S 输出 | +| 9x 舵机 | **必须 180° 标准舵机**(如 KPower M0090 或 MG90S 180° 金属齿轮版),详见下方舵机选型说明 | +| Raspberry Pi Pico (RP2040) | 舵机控制 | +| 6 Pin PicoBlade 连接线 | RP2040 ↔ ESP32 UART | + +### 4.3 PCB 飞线操作(3 根线) + +在 CogNog V1.0 PCB 上,**切断原走线并飞线到新引脚**: + +| 原始引脚 | 飞线到 | 摄像头信号 | 说明 | +|----------|--------|-----------|------| +| GPIO 35 | **GPIO 14** | CAMERA_PIN_D7 | 数据位 7 | +| GPIO 36 | **GPIO 41** | CAMERA_PIN_VSYNC | 垂直同步 | +| GPIO 37 | **GPIO 42** | CAMERA_PIN_HREF | 行参考信号 | + +> **注意**:camera-version 分支还释放了 JTAG 引脚(GPIO 39-42)给摄像头使用,代码中通过 `gpio_reset_pin()` 实现。 + +### 4.4 代码下载 + +```bash +# 第 1 步:克隆 camera-version 分支(ESP32 固件 + RP2040 代码都在里面) +git clone -b camera-version https://github.com/will-cogley/CogletESP.git + +# 第 2 步:克隆主仓库(文档、PCB 原理图、3D 打印件) +git clone https://github.com/will-cogley/Coglet.git +``` + +克隆后的目录结构: + +``` +CogletESP/ # camera-version 分支 +├── main/ +│ └── boards/ +│ └── bread-compact-wifi-s3cam/ +│ ├── config.h # GPIO 引脚映射(飞线后的版本) +│ └── compact_wifi_board_s3cam.cc # 板级初始化(禁用 LCD,启用摄像头) +├── components/ +├── RP2040/ # RP2040 MicroPython 代码 +│ ├── main.py # 主控程序、舵机状态机、UART 通信(ESP32 + Grove Vision AI V2) +│ ├── servoclass.py # 舵机驱动(PWM 50Hz,平滑运动) +│ └── animation.py # 动画定义(思考、开心、热身等) +├── CMakeLists.txt +└── sdkconfig +``` + +### 4.5 编译烧录 ESP32 固件(macOS) + +```bash +# 1. 进入项目目录 +cd CogletESP + +# 2. 激活 IDF 环境 +source ~/esp/esp-idf/export.sh + +# 3. 设置目标芯片 +idf.py set-target esp32s3 + +# 4. 配置板级选项 +idf.py menuconfig +# → 找到板级配置,选择 bread-compact-wifi-s3cam + +# 5. 编译 +idf.py build + +# 6. 查看可用串口 +ls /dev/cu.usb* + +# 7. 烧录并监控 +idf.py -p /dev/cu.usbmodem14101 flash monitor +# 串口名根据实际替换(/dev/cu.usbmodem* 或 /dev/cu.usbserial*) + +# 8. 退出监视器:Ctrl + ] +``` + +### 4.6 烧录 RP2040(MicroPython) + +**第 1 步:刷入 MicroPython 固件** + +下载地址:https://micropython.org/download/RPI_PICO/ + +**版本选择**:下载 **v1.24.x ~ v1.25.x 稳定版** `.uf2` 文件。代码只用基础 API(Pin、PWM、UART),v1.20+ 稳定版都兼容。**不要下载 preview/nightly 预览版。** + +**硬件说明**:CogNog V1.0 PCB 上 RP2040 是直接焊接的(不是独立的 Raspberry Pi Pico 开发板),PCB 上有两个相关按键: +- **SW1(Boot Switch)**:位于 Flash Memory 旁,即 BOOTSEL 功能,用于进入 UF2 烧录模式 +- **Run Switch**:位于 RP2040 旁,连接 RUN 引脚,即**复位按钮**。使用场景: + - 上传新的 .py 文件后,按一下重启 RP2040 使新代码生效(等同于 `mpremote reset`) + - 舵机行为异常时,按一下重启恢复到初始状态 + - 配合 SW1 进入烧录模式(见下方方式 B) + +操作(macOS / Windows 通用): + +**方式 A — USB 未连接时:** +1. **按住 SW1(Boot Switch)** → 通过 RP2040 的 USB-C 口连接电脑 → 松开 SW1 +2. 电脑上出现 `RPI-RP2` U 盘(macOS 在 Finder,Windows 在资源管理器) +3. 将 `.uf2` 文件拖入 U 盘 +4. RP2040 自动重启 + +**方式 B — USB 已连接时(更常用):** +1. **按住 SW1(Boot Switch)不松手** +2. **按一下 Run Switch(复位)然后松开**(只按一下,不用保持) +3. **松开 SW1** — 整个过程约 1-2 秒,关键是按 Run Switch 时 SW1 必须处于按下状态 +4. 电脑上出现 `RPI-RP2` U 盘 +5. 将 `.uf2` 文件拖入 U 盘 +6. RP2040 自动重启 + +> **原理**:Run Switch 让 RP2040 复位重启,重启瞬间 SW1 被按着 → RP2040 检测到 BOOTSEL 为低电平 → 进入 UF2 bootloader 模式。 +> +> **提示**:如果 RP2040 已经刷过 MicroPython 且只需要更新 .py 文件,不需要重新进入 bootloader 模式,直接用 `mpremote` 上传即可(见第 2 步)。 + +**第 2 步:上传 .py 文件** + +> **注意**:`CogletESP` 分支有 4 个文件(含 `coms.py`),`camera-version` 分支有 3 个文件(无 `coms.py`)。请使用对应分支的文件。 + +#### macOS + +方式 A — mpremote(推荐): + +```bash +pip install mpremote +cd CogletESP/RP2040 + +mpremote cp main.py :main.py +mpremote cp servoclass.py :servoclass.py +mpremote cp coms.py :coms.py # 仅 CogletESP 分支需要 +mpremote cp animation.py :animation.py + +mpremote reset # 重启运行 +mpremote repl # 查看串口输出(调试用) +``` + +mpremote 本质就是一个串口文件传输工具,把 .py 文件拷贝到 Pico 的文件系统里。Pico 上电后自动运行 main.py,不需要搭建任何 MicroPython 编译环境。 + +方式 B — Thonny(图形界面): + +```bash +brew install --cask thonny +``` + +1. 打开 Thonny → 右下角选择 `MicroPython (Raspberry Pi Pico)` +2. 逐个打开 .py 文件 → 另存为 → 选择 `Raspberry Pi Pico` → 保存同名 +3. 保存完成后 Pico 重启自动运行 `main.py` + +#### Windows + +方式 A — mpremote(推荐): + +```powershell +# 1. 安装 mpremote(需要 Python 3.x,从 python.org 下载安装,勾选 Add to PATH) +pip install mpremote + +# 2. 进入 RP2040 目录 +cd CogletESP\RP2040 + +# 3. 上传文件(Pico 连接 USB 后 Windows 会分配 COM 口,mpremote 自动识别) +mpremote cp main.py :main.py +mpremote cp servoclass.py :servoclass.py +mpremote cp coms.py :coms.py # 仅 CogletESP 分支需要 +mpremote cp animation.py :animation.py + +mpremote reset # 重启运行 +mpremote repl # 查看串口输出(调试用,Ctrl+] 退出) +``` + +> **Windows 注意事项**: +> - 如果 `mpremote` 找不到设备,打开**设备管理器 → 端口(COM 和 LPT)**,确认 Pico 对应的 COM 口(如 COM3),然后用 `mpremote connect COM3 cp main.py :main.py` 指定端口 +> - 如果设备管理器中看不到 COM 口,需要安装驱动:MicroPython 固件刷入后 Pico 通常免驱,若未识别可尝试拔插 USB 或换 USB 口 + +方式 B — Thonny(图形界面,适合新手): + +1. 下载安装 Thonny:https://thonny.org/ (选择 Windows 版本) +2. 打开 Thonny → 右下角选择 `MicroPython (Raspberry Pi Pico)` +3. 逐个打开 .py 文件 → 文件 → 另存为 → 选择 `Raspberry Pi Pico` → 保存同名 +4. 保存完成后 Pico 重启自动运行 `main.py` + +### 4.7 配置 Grove Vision AI V2(人脸追踪) + +**不需要手动刷底层固件**,但需要部署一个人脸检测模型。 + +**操作步骤:** + +1. 用 USB-C 线将 Grove Vision AI V2 连接到电脑 +2. 用 Chrome 浏览器访问 **SenseCraft AI 平台**:https://sensecraft.seeed.cc/ +3. 模型下载地址:https://sensecraft.seeed.cc/ai/model/deploy?id=60094&uniform_type=36&name=%E4%BA%BA%E8%84%B8%E6%A3%80%E6%B5%8B&adapteds=11&adapteds=12&adapteds=14&task=1 +4. 选择一个**人脸检测模型**(推荐 YOLO Face Detection,输入尺寸 **224x224**) +5. 点击部署,等待上传完成 +6. 断开 USB,将模块接回 RP2040 的 UART + +**为什么是 224x224?** 代码中 `pixel_centre = 112` 即 224/2,表明模型输入分辨率为 224x224。 + +**工作原理:** + +``` +RP2040 发送 AT+INVOKE=1,0,1 (SSCMA AT 协议) + ↓ +Grove Vision AI V2 运行人脸检测推理 + ↓ +返回 JSON,包含 "boxes" 字段 → [x, y, w, h, ...] + ↓ +RP2040 计算人脸偏移量:x_offset = boxes[0] - 112, y_offset = boxes[1] - 112 + ↓ +驱动舵机追踪: + - EYL/EYR(眼球左右) → 跟随 x_offset + - PIT(头部俯仰) → 跟随 y_offset + - YAW(底座旋转) → 眼球偏离中心 >20° 时延迟跟随 + ↓ +deadzone = 20 像素(避免微小抖动触发舵机) +``` + +### 4.8 硬件连接 + +``` +┌─────────────┐ UART 115200 ┌──────────────┐ UART 921600 ┌───────────────────┐ +│ ESP32-S3 │◄──────────────────►│ RP2040 │◄──────────────────►│ Grove Vision AI V2│ +│ │ TX→RX(GP5) │ (Pico) │ TX(GP0)→RX │ │ +│ AI/语音 │ RX←TX(GP4) │ 舵机控制 │ RX(GP1)←TX │ 人脸检测 │ +│ WiFi/网络 │ GND──GND │ 动画状态机 │ │ YOLO 模型 │ +└─────────────┘ └──────────────┘ └───────────────────┘ + │ + PWM 引脚 x9 + │ + ┌──────┴──────┐ + │ 9 个舵机 │ + │ EYL/EYR/PIT │ + │ YAW/MOU/LID │ + │ + 耳朵等 │ + └─────────────┘ +``` + +ESP32 通过 UART 发送状态字符串给 RP2040: +`neutral` / `idle` / `listening` / `speaking` / `thinking` / `happy` +→ RP2040 根据状态执行对应舵机动画 + +### 4.9 舵机选型说明(重要) + +> **实测踩坑记录**:使用 MG90S 360° 连续旋转版舵机后,耳朵舵机转到目标角度后无法停止,持续堵转导致齿轮发出刺耳声音、舵机严重发烫,有烧毁风险。更换为 180° 标准舵机后问题解决。 + +#### 必须使用 180° 标准舵机的原因 + +Coglet 的 9 个舵机全部采用**角度控制**模式(代码中 `set_target(角度)` 命令舵机转到指定角度并保持),这只有 180° 标准舵机才能实现。 + +**180° 标准舵机 vs 360° 连续旋转舵机的核心区别:** + +| 对比项 | 180° 标准舵机(如 KPower M0090) | 360° 连续旋转舵机(如 MG90S 360° 改装版) | +|--------|-------------------------------|-------------------------------------| +| **内部结构** | 有电位器(可变电阻),实时反馈当前角度 | 拆除/固定了电位器,失去角度反馈能力 | +| **PWM 信号含义** | 对应**目标角度**(1ms=0°, 1.5ms=90°, 2ms=180°) | 对应**旋转速度和方向**(1.5ms=停止, <1.5ms=反转, >1.5ms=正转) | +| **控制逻辑** | 闭环控制:收到 PWM → 对比目标与当前角度 → 自动转到位停住 | 开环控制:收到 PWM → 按速度持续旋转,永不停止 | +| **能否锁定位置** | 能,到达角度后施力保持 | 不能,停转后无保持力,外力可推动 | +| **旋转范围** | 0°~180° 精确定位 | 360° 无限旋转,无法精确定位 | + +#### 为什么 360° 舵机无法通过代码适配? + +网上有"定时转动"方案(全速旋转 N 毫秒 → 发停止信号),原理是 `转动时间 = (500ms / 360°) × 目标角度`。但这对 Coglet **完全不可行**: + +1. **误差累积无法修正**:没有位置反馈,每次转动误差 ±5°~10°。Coglet 的动画是高频反复运动(说话时嘴巴每 250ms 开合一次、耳朵每秒摆动),运行几分钟后累积误差可达几百度,位置完全跑飞 +2. **个体差异大**:每台舵机电机特性、齿轮间隙不同,无法统一校准"时间-角度"关系。换一台舵机就要重新标定 +3. **无法保持位置**:代码中头部俯仰、眼球等需要停在某个角度并持续施力保持。360° 舵机停转后没有保持力,手一碰就偏了 +4. **实时性失效**:Coglet 需要实时响应 AI 状态变化动态调整角度,定时方案无法做到实时同步 +5. **负载和温度影响转速**:电压波动、温度变化都会改变旋转速度,使时间估算更不准确 + +#### 推荐舵机型号 + +| 型号 | 说明 | 参考价格 | +|------|------|---------| +| **KPower M0090**(官方推荐) | 9g 模拟金属齿轮 180° 舵机 | ~¥8-12/个 | +| **MG90S 180° 金属齿轮版** | 注意必须是 **180° 版**,不带 "continuous/360" 字样 | ~¥5-8/个 | + +> **购买注意**:MG90S 有 180° 和 360° 两个版本,外观完全一样。购买时务必确认商品标题或参数中标注 "180°",避免买到 360° 连续旋转版。 + +#### 9 个舵机角度范围详解 + +代码中所有舵机的 PWM 映射为 0°~180°(脉宽 500μs~2500μs),各舵机通过 `min_angle` / `max_angle` 限定实际运动范围(源码:`animation.py` 第 14-23 行): + +| 舵机代号 | 功能 | GPIO 引脚 | 角度范围 | 最大跨度 | 运动说明 | +|---------|------|----------|---------|---------|---------| +| **YAW** | 底座旋转 | GP6 | 10°~170° | 160° | 头部左右转动,人脸追踪时由 Grove Vision AI V2 驱动 | +| **ROL** | 颈部侧倾 | GP7 | 30°~120° | 90° | 头部左右歪头,happy 状态下 70°↔110° 摆动 | +| **PIT** | 头部俯仰 | GP8 | 1°~80° | 79° | 头部上下点头,thinking 状态下 50°↔80° 摆动 | +| **MOU** | 嘴巴开合 | GP19 | 5°~150° | 145° | speaking 时 70°↔130° 每 250ms 切换(张嘴/闭嘴) | +| **EYL** | 左眼球 | GP12 | 30°~150° | 120° | 左右看,人脸追踪时跟随 x 偏移量 | +| **EYR** | 右眼球 | GP13 | 30°~150° | 120° | 与 EYL 同步运动 | +| **LID** | 眼睑 | GP14 | 30°~160° | 130° | 30°=闭眼,110°~160°=睁眼,随机眨眼动画 | +| **EAL** | 左耳 | GP15 | 60°~150° | 90° | happy 状态下 100°↔160° 摆动 | +| **EAR** | 右耳 | GP16 | 30°~120° | 90° | happy 状态下 60°↔120° 摆动 | + +> **注意**:以上角度范围是代码中的软件限位,基于官方 3D 打印件和 KPower M0090 舵机校准。如果使用其他舵机或自制外壳,可能需要调整 `animation.py` 中的 `min_angle` / `max_angle` 避免堵转。 + +> **MOU 引脚差异**:`CogletESP` 分支 MOU 使用 **GP19**,`camera-version` 分支 MOU 使用 **GP9**。请根据实际 PCB 版本确认。 + +#### 校准模式使用方法 + +CogNog V1.0 PCB 上有一个 **SW11(Calibration Switch)** 拨动开关,连接 RP2040 的 GPIO20。代码中 GPIO20 配置了内部上拉电阻: + +```python +mode = Pin(20, Pin.IN, Pin.PULL_UP) +is_calibrating = (mode.value() == 1) # 高电平 = 校准模式 +``` + +**SW11 逻辑:** + +| SW11 状态 | GPIO20 电平 | 模式 | 表现 | +|----------|-----------|------|------| +| 断开(GPIO20 悬空) | 高(内部上拉到 1) | **校准模式** | 所有舵机归 90° 中位,LED 闪烁 | +| 接通(GPIO20 接 GND) | 低 | **正常运行模式** | 响应 ESP32 状态指令,执行动画 | + +> **提示**:如果不确定 SW11 哪个位置对应哪种模式,两个位置都试一下,**LED 闪烁的那个就是校准模式**。 + +#### 校准与组装流程 + +**前提**:RP2040 已刷入 MicroPython 固件并上传 .py 文件。 + +``` +第 1 步:进入校准模式 + └→ 将 SW11 拨到校准位置(LED 闪烁) + +第 2 步:通电 + └→ 给 RP2040 和舵机供电 + └→ 所有 9 个舵机自动转到 90° 中位(staggered startup,逐个上电避免电流冲击) + +第 3 步:安装舵机臂 + └→ 在 90° 中位状态下,将舵机臂安装到需要的朝向 + └→ 拧紧舵机臂固定螺丝 + └→ ⚠️ 关键:必须在通电校准状态下安装,否则角度对不上 + +第 4 步:组装机械结构 + └→ 将舵机装入 3D 打印外壳 + └→ 连接所有机械连杆 + +第 5 步:验证 + └→ 将 SW11 拨回正常运行模式 + └→ 观察舵机是否能正常运动,无堵转 + └→ 如有堵转,调整 animation.py 中对应舵机的 min_angle / max_angle + +第 6 步:连接 ESP32 + └→ 接上 ESP32 UART(TX→GP5, RX→GP4) + └→ ESP32 发送状态指令,舵机开始响应 AI 对话动画 +``` + +> **校准模式不需要断开 ESP32**:校准模式在主循环中每帧都强制覆盖舵机状态(`main.py` 第 153-155 行),即使 ESP32 发送了指令也会被忽略。 + +### 4.10 camera-version 的代价与限制 + +| 项目 | 说明 | +|------|------| +| **LCD 屏被禁用** | 摄像头占用了原 LCD 引脚,代码用 DummyDisplay 空实现替代 | +| **音频引脚全部重映射** | MIC 从 GPIO 1/2/42 移到 4/5/6,SPK 从 GPIO 39/40/41 移到 7/15/16 | +| **内存压力** | 摄像头 + PSRAM 同时运行可能偶发内存不足(作者提到 "appears to run out of memory sometimes") | +| **摄像头画面翻转** | 已通过代码设置 `SetHMirror(true)` + `SetVFlip(true)` 修正 | + +--- + +## 五、无摄像头版本搭建流程(CogletESP 分支) + +> 如果不使用 ESP32 OV3660 摄像头,想保留 LCD 显示,使用此方案。 + +### 5.1 代码下载 + +```bash +git clone -b CogletESP https://github.com/will-cogley/CogletESP.git +git clone https://github.com/will-cogley/Coglet.git +``` + +### 5.2 ESP32 编译烧录 + +与摄像头版本相同(参见 4.5),但 menuconfig 中的板级配置可能不同,PCB **无需飞线**。 + +### 5.3 RP2040 烧录 + +MicroPython 固件刷入方式与摄像头版本相同(参见 4.6),但 **RP2040 代码两个分支不同**: +- `CogletESP` 分支有 **4 个文件**:`main.py`、`servoclass.py`、`coms.py`、`animation.py` +- `camera-version` 分支只有 **3 个文件**(无 `coms.py`,UART 通信集成在 `main.py` 中) + +请使用对应分支的 RP2040 目录文件上传。 + +### 5.4 Grove Vision AI V2 + +与摄像头版本完全相同(参见 4.7),Grove Vision AI V2 的人脸追踪功能由 RP2040 端控制,与 ESP32 分支选择无关。 + +--- + +## 六、常见问题 + +| 问题 | 解决方案 | +|------|---------| +| Python 环境冲突 | `idf.py fullclean` 后重新编译 | +| Bootloader CMake 缓存不匹配 | `rm -rf build/bootloader build/bootloader-prefix` | +| 找不到串口设备 | 安装 CP2102/CH340 驱动,检查 USB 线是否支持数据传输 | +| menuconfig 中找不到板级配置 | 确认在正确的分支(`camera-version` 或 `CogletESP`) | +| 摄像头不工作 | 确认已完成 3 根飞线(35→14, 36→41, 37→42)并使用 `camera-version` 分支 | +| 偶发内存不足 | camera-version 已知问题,摄像头 + PSRAM 同时运行时可能出现 | +| Grove Vision AI V2 无响应 | 确认已通过 SenseCraft 部署人脸检测模型,UART 波特率 921600 | +| 舵机不动 | 检查 RP2040 是否正确上传 .py 文件(CogletESP 分支 4 个 / camera-version 分支 3 个),UART 连接是否正常 | +| 舵机堵转、发烫、齿轮刺耳声 | **使用了 360° 连续旋转舵机**,必须更换为 180° 标准舵机(详见 4.9 舵机选型说明) | +| 舵机持续朝一个方向旋转不停 | 同上,360° 舵机收到非 90° 信号会持续旋转。180° 舵机会转到目标角度后自动停住 | + +--- + +## 七、参考资源 + +| 资源 | 地址 | +|------|------| +| Coglet GitHub 主仓库 | https://github.com/will-cogley/Coglet | +| CogletESP 固件仓库 | https://github.com/will-cogley/CogletESP | +| 小智 ESP32 原版 | https://github.com/78/xiaozhi-esp32 | +| 眼球机构参考 | https://github.com/will-cogley/EyeMech_Epsilon | +| Coglet 组装视频 | https://www.youtube.com/watch?v=-7I-jFSNP2E | +| MicroPython 固件下载 | https://micropython.org/download/RPI_PICO/ | +| ESP-IDF 官方文档 | https://docs.espressif.com/projects/esp-idf/zh_CN/v5.4.2/ | +| MicroPython 官方文档 | https://docs.micropython.org/en/latest/ | +| mpremote 工具文档 | https://docs.micropython.org/en/latest/reference/mpremote.html | +| SenseCraft AI 平台(Grove Vision AI V2 模型部署) | https://sensecraft.seeed.cc/ | +| Grove Vision AI V2 Wiki | https://wiki.seeedstudio.com/grove_vision_ai_v2/ | diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..e90b554 --- /dev/null +++ b/LICENSE @@ -0,0 +1,22 @@ +MIT License + +Copyright (c) 2025 Shenzhen Xinzhi Future Technology Co., Ltd. +Copyright (c) 2025 Project Contributors + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/README.md b/README.md new file mode 100644 index 0000000..9e8c70d --- /dev/null +++ b/README.md @@ -0,0 +1,172 @@ +# An MCP-based Chatbot + +(English | [中文](README_zh.md) | [日本語](README_ja.md)) + +## Introduction + +👉 [Human: Give AI a camera vs AI: Instantly finds out the owner hasn't washed hair for three days【bilibili】](https://www.bilibili.com/video/BV1bpjgzKEhd/) + +👉 [Handcraft your AI girlfriend, beginner's guide【bilibili】](https://www.bilibili.com/video/BV1XnmFYLEJN/) + +As a voice interaction entry, the XiaoZhi AI chatbot leverages the AI capabilities of large models like Qwen / DeepSeek, and achieves multi-terminal control via the MCP protocol. + +Control everything via MCP + +## Version Notes + +The current v2 version is incompatible with the v1 partition table, so it is not possible to upgrade from v1 to v2 via OTA. For partition table details, see [partitions/v2/README.md](partitions/v2/README.md). + +All hardware running v1 can be upgraded to v2 by manually flashing the firmware. + +The stable version of v1 is 1.9.2. You can switch to v1 by running `git checkout v1`. The v1 branch will be maintained until February 2026. + +### Features Implemented + +- Wi-Fi / ML307 Cat.1 4G +- Offline voice wake-up [ESP-SR](https://github.com/espressif/esp-sr) +- Supports two communication protocols ([Websocket](docs/websocket.md) or MQTT+UDP) +- Uses OPUS audio codec +- Voice interaction based on streaming ASR + LLM + TTS architecture +- Speaker recognition, identifies the current speaker [3D Speaker](https://github.com/modelscope/3D-Speaker) +- OLED / LCD display, supports emoji display +- Battery display and power management +- Multi-language support (Chinese, English, Japanese) +- Supports ESP32-C3, ESP32-S3, ESP32-P4 chip platforms +- Device-side MCP for device control (Speaker, LED, Servo, GPIO, etc.) +- Cloud-side MCP to extend large model capabilities (smart home control, PC desktop operation, knowledge search, email, etc.) +- Customizable wake words, fonts, emojis, and chat backgrounds with online web-based editing ([Custom Assets Generator](https://github.com/78/xiaozhi-assets-generator)) + +## Hardware + +### Breadboard DIY Practice + +See the Feishu document tutorial: + +👉 ["XiaoZhi AI Chatbot Encyclopedia"](https://ccnphfhqs21z.feishu.cn/wiki/F5krwD16viZoF0kKkvDcrZNYnhb?from=from_copylink) + +Breadboard demo: + +![Breadboard Demo](docs/v1/wiring2.jpg) + +### Supports 70+ Open Source Hardware (Partial List) + +- LiChuang ESP32-S3 Development Board +- Espressif ESP32-S3-BOX3 +- M5Stack CoreS3 +- M5Stack AtomS3R + Echo Base +- Magic Button 2.4 +- Waveshare ESP32-S3-Touch-AMOLED-1.8 +- LILYGO T-Circle-S3 +- XiaGe Mini C3 +- CuiCan AI Pendant +- WMnologo-Xingzhi-1.54TFT +- SenseCAP Watcher +- ESP-HI Low Cost Robot Dog + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +## Software + +### Firmware Flashing + +For beginners, it is recommended to use the firmware that can be flashed without setting up a development environment. + +The firmware connects to the official [xiaozhi.me](https://xiaozhi.me) server by default. Personal users can register an account to use the Qwen real-time model for free. + +👉 [Beginner's Firmware Flashing Guide](https://ccnphfhqs21z.feishu.cn/wiki/Zpz4wXBtdimBrLk25WdcXzxcnNS) + +### Development Environment + +- Cursor or VSCode +- Install ESP-IDF plugin, select SDK version 5.4 or above +- Linux is better than Windows for faster compilation and fewer driver issues +- This project uses Google C++ code style, please ensure compliance when submitting code + +### Developer Documentation + +- [Custom Board Guide](docs/custom-board.md) - Learn how to create custom boards for XiaoZhi AI +- [MCP Protocol IoT Control Usage](docs/mcp-usage.md) - Learn how to control IoT devices via MCP protocol +- [MCP Protocol Interaction Flow](docs/mcp-protocol.md) - Device-side MCP protocol implementation +- [MQTT + UDP Hybrid Communication Protocol Document](docs/mqtt-udp.md) +- [A detailed WebSocket communication protocol document](docs/websocket.md) + +## Large Model Configuration + +If you already have a XiaoZhi AI chatbot device and have connected to the official server, you can log in to the [xiaozhi.me](https://xiaozhi.me) console for configuration. + +👉 [Backend Operation Video Tutorial (Old Interface)](https://www.bilibili.com/video/BV1jUCUY2EKM/) + +## Related Open Source Projects + +For server deployment on personal computers, refer to the following open-source projects: + +- [xinnan-tech/xiaozhi-esp32-server](https://github.com/xinnan-tech/xiaozhi-esp32-server) Python server +- [joey-zhou/xiaozhi-esp32-server-java](https://github.com/joey-zhou/xiaozhi-esp32-server-java) Java server +- [AnimeAIChat/xiaozhi-server-go](https://github.com/AnimeAIChat/xiaozhi-server-go) Golang server + +Other client projects using the XiaoZhi communication protocol: + +- [huangjunsen0406/py-xiaozhi](https://github.com/huangjunsen0406/py-xiaozhi) Python client +- [TOM88812/xiaozhi-android-client](https://github.com/TOM88812/xiaozhi-android-client) Android client +- [100askTeam/xiaozhi-linux](http://github.com/100askTeam/xiaozhi-linux) Linux client by 100ask +- [78/xiaozhi-sf32](https://github.com/78/xiaozhi-sf32) Bluetooth chip firmware by Sichuan +- [QuecPython/solution-xiaozhiAI](https://github.com/QuecPython/solution-xiaozhiAI) QuecPython firmware by Quectel + +Custom Assets Tools: + +- [78/xiaozhi-assets-generator](https://github.com/78/xiaozhi-assets-generator) Custom Assets Generator (Wake words, fonts, emojis, backgrounds) + +## About the Project + +This is an open-source ESP32 project, released under the MIT license, allowing anyone to use it for free, including for commercial purposes. + +We hope this project helps everyone understand AI hardware development and apply rapidly evolving large language models to real hardware devices. + +If you have any ideas or suggestions, please feel free to raise Issues or join the QQ group: 1011329060 + +## Star History + + + + + + Star History Chart + + diff --git a/README_ja.md b/README_ja.md new file mode 100644 index 0000000..ea7f70f --- /dev/null +++ b/README_ja.md @@ -0,0 +1,168 @@ +# MCP ベースのチャットボット + +(日本語 | [中文](README_zh.md) | [English](README.md)) + +## はじめに + +👉 [人間:AIにカメラを装着 vs AI:その場で飼い主が3日間髪を洗っていないことを発見【bilibili】](https://www.bilibili.com/video/BV1bpjgzKEhd/) + +👉 [手作りでAIガールフレンドを作る、初心者入門チュートリアル【bilibili】](https://www.bilibili.com/video/BV1XnmFYLEJN/) + +シャオジーAIチャットボットは音声インタラクションの入口として、Qwen / DeepSeekなどの大規模モデルのAI能力を活用し、MCPプロトコルを通じてマルチエンド制御を実現します。 + +MCPであらゆるものを制御 + +## バージョンノート + +現在のv2バージョンはv1パーティションテーブルと互換性がないため、v1からv2へOTAでアップグレードすることはできません。パーティションテーブルの詳細については、[partitions/v2/README.md](partitions/v2/README.md)をご参照ください。 + +v1を実行しているすべてのハードウェアは、ファームウェアを手動で書き込むことでv2にアップグレードできます。 + +v1の安定版は1.9.2です。`git checkout v1`でv1に切り替えることができます。v1ブランチは2026年2月まで継続的にメンテナンスされます。 + +### 実装済み機能 + +- Wi-Fi / ML307 Cat.1 4G +- オフライン音声ウェイクアップ [ESP-SR](https://github.com/espressif/esp-sr) +- 2種類の通信プロトコルに対応([Websocket](docs/websocket.md) または MQTT+UDP) +- OPUSオーディオコーデックを採用 +- ストリーミングASR + LLM + TTSアーキテクチャに基づく音声インタラクション +- 話者認識、現在話している人を識別 [3D Speaker](https://github.com/modelscope/3D-Speaker) +- OLED / LCDディスプレイ、表情表示対応 +- バッテリー表示と電源管理 +- 多言語対応(中国語、英語、日本語) +- ESP32-C3、ESP32-S3、ESP32-P4チッププラットフォーム対応 +- デバイス側MCPによるデバイス制御(音量・明るさ調整、アクション制御など) +- クラウド側MCPで大規模モデル能力を拡張(スマートホーム制御、PCデスクトップ操作、知識検索、メール送受信など) +- カスタマイズ可能なウェイクワード、フォント、絵文字、チャット背景、オンラインWeb編集に対応 ([カスタムアセットジェネレーター](https://github.com/78/xiaozhi-assets-generator)) + +## ハードウェア + +### ブレッドボード手作り実践 + +Feishuドキュメントチュートリアルをご覧ください: + +👉 [「シャオジーAIチャットボット百科事典」](https://ccnphfhqs21z.feishu.cn/wiki/F5krwD16viZoF0kKkvDcrZNYnhb?from=from_copylink) + +ブレッドボードのデモ: + +![ブレッドボードデモ](docs/v1/wiring2.jpg) + +### 70種類以上のオープンソースハードウェアに対応(一部のみ表示) + +- 立創・実戦派 ESP32-S3 開発ボード +- 楽鑫 ESP32-S3-BOX3 +- M5Stack CoreS3 +- M5Stack AtomS3R + Echo Base +- マジックボタン2.4 +- 微雪電子 ESP32-S3-Touch-AMOLED-1.8 +- LILYGO T-Circle-S3 +- エビ兄さん Mini C3 +- CuiCan AIペンダント +- 無名科技Nologo-星智-1.54TFT +- SenseCAP Watcher +- ESP-HI 超低コストロボット犬 + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +## ソフトウェア + +### ファームウェア書き込み + +初心者の方は、まず開発環境を構築せずに書き込み可能なファームウェアを使用することをおすすめします。 + +ファームウェアはデフォルトで公式 [xiaozhi.me](https://xiaozhi.me) サーバーに接続します。個人ユーザーはアカウント登録でQwenリアルタイムモデルを無料で利用できます。 + +👉 [初心者向けファームウェア書き込みガイド](https://ccnphfhqs21z.feishu.cn/wiki/Zpz4wXBtdimBrLk25WdcXzxcnNS) + +### 開発環境 + +- Cursor または VSCode +- ESP-IDFプラグインをインストールし、SDKバージョン5.4以上を選択 +- LinuxはWindowsよりも優れており、コンパイルが速く、ドライバの問題も少ない +- 本プロジェクトはGoogle C++コードスタイルを採用、コード提出時は準拠を確認してください + +### 開発者ドキュメント + +- [カスタム開発ボードガイド](docs/custom-board.md) - シャオジーAI用のカスタム開発ボード作成方法 +- [MCPプロトコルIoT制御使用法](docs/mcp-usage.md) - MCPプロトコルでIoTデバイスを制御する方法 +- [MCPプロトコルインタラクションフロー](docs/mcp-protocol.md) - デバイス側MCPプロトコルの実装方法 +- [MQTT + UDP ハイブリッド通信プロトコルドキュメント](docs/mqtt-udp.md) +- [詳細なWebSocket通信プロトコルドキュメント](docs/websocket.md) + +## 大規模モデル設定 + +すでにシャオジーAIチャットボットデバイスをお持ちで、公式サーバーに接続済みの場合は、[xiaozhi.me](https://xiaozhi.me) コンソールで設定できます。 + +👉 [バックエンド操作ビデオチュートリアル(旧インターフェース)](https://www.bilibili.com/video/BV1jUCUY2EKM/) + +## 関連オープンソースプロジェクト + +個人PCでサーバーをデプロイする場合は、以下のオープンソースプロジェクトを参照してください: + +- [xinnan-tech/xiaozhi-esp32-server](https://github.com/xinnan-tech/xiaozhi-esp32-server) Pythonサーバー +- [joey-zhou/xiaozhi-esp32-server-java](https://github.com/joey-zhou/xiaozhi-esp32-server-java) Javaサーバー +- [AnimeAIChat/xiaozhi-server-go](https://github.com/AnimeAIChat/xiaozhi-server-go) Golangサーバー + +シャオジー通信プロトコルを利用した他のクライアントプロジェクト: + +- [huangjunsen0406/py-xiaozhi](https://github.com/huangjunsen0406/py-xiaozhi) Pythonクライアント +- [TOM88812/xiaozhi-android-client](https://github.com/TOM88812/xiaozhi-android-client) Androidクライアント +- [100askTeam/xiaozhi-linux](http://github.com/100askTeam/xiaozhi-linux) 百問科技提供のLinuxクライアント +- [78/xiaozhi-sf32](https://github.com/78/xiaozhi-sf32) 思澈科技のBluetoothチップファームウェア +- [QuecPython/solution-xiaozhiAI](https://github.com/QuecPython/solution-xiaozhiAI) 移遠提供のQuecPythonファームウェア + +## プロジェクトについて + +これはエビ兄さんがオープンソースで公開しているESP32プロジェクトで、MITライセンスのもと、誰でも無料で、商用利用も可能です。 + +このプロジェクトを通じて、AIハードウェア開発を理解し、急速に進化する大規模言語モデルを実際のハードウェアデバイスに応用できるようになることを目指しています。 + +ご意見やご提案があれば、いつでもIssueを提出するか、QQグループ:1011329060 にご参加ください。 + +## スター履歴 + + + + + + Star History Chart + + diff --git a/README_zh.md b/README_zh.md new file mode 100644 index 0000000..e7ad1fa --- /dev/null +++ b/README_zh.md @@ -0,0 +1,168 @@ +# An MCP-based Chatbot + +(中文 | [English](README.md) | [日本語](README_ja.md)) + +## 介绍 + +👉 [人类:给 AI 装摄像头 vs AI:当场发现主人三天没洗头【bilibili】](https://www.bilibili.com/video/BV1bpjgzKEhd/) + +👉 [手工打造你的 AI 女友,新手入门教程【bilibili】](https://www.bilibili.com/video/BV1XnmFYLEJN/) + +小智 AI 聊天机器人作为一个语音交互入口,利用 Qwen / DeepSeek 等大模型的 AI 能力,通过 MCP 协议实现多端控制。 + +通过MCP控制万物 + +### 版本说明 + +当前 v2 版本与 v1 版本分区表不兼容,所以无法从 v1 版本通过 OTA 升级到 v2 版本。分区表说明参见 [partitions/v2/README.md](partitions/v2/README.md)。 + +使用 v1 版本的所有硬件,可以通过手动烧录固件来升级到 v2 版本。 + +v1 的稳定版本为 1.9.2,可以通过 `git checkout v1` 来切换到 v1 版本,该分支会持续维护到 2026 年 2 月。 + +### 已实现功能 + +- Wi-Fi / ML307 Cat.1 4G +- 离线语音唤醒 [ESP-SR](https://github.com/espressif/esp-sr) +- 支持两种通信协议([Websocket](docs/websocket.md) 或 MQTT+UDP) +- 采用 OPUS 音频编解码 +- 基于流式 ASR + LLM + TTS 架构的语音交互 +- 声纹识别,识别当前说话人的身份 [3D Speaker](https://github.com/modelscope/3D-Speaker) +- OLED / LCD 显示屏,支持表情显示 +- 电量显示与电源管理 +- 支持多语言(中文、英文、日文) +- 支持 ESP32-C3、ESP32-S3、ESP32-P4 芯片平台 +- 通过设备端 MCP 实现设备控制(音量、灯光、电机、GPIO 等) +- 通过云端 MCP 扩展大模型能力(智能家居控制、PC桌面操作、知识搜索、邮件收发等) +- 自定义唤醒词、字体、表情与聊天背景,支持网页端在线修改 ([自定义Assets生成器](https://github.com/78/xiaozhi-assets-generator)) + +## 硬件 + +### 面包板手工制作实践 + +详见飞书文档教程: + +👉 [《小智 AI 聊天机器人百科全书》](https://ccnphfhqs21z.feishu.cn/wiki/F5krwD16viZoF0kKkvDcrZNYnhb?from=from_copylink) + +面包板效果图如下: + +![面包板效果图](docs/v1/wiring2.jpg) + +### 支持 70 多个开源硬件(仅展示部分) + +- 立创·实战派 ESP32-S3 开发板 +- 乐鑫 ESP32-S3-BOX3 +- M5Stack CoreS3 +- M5Stack AtomS3R + Echo Base +- 神奇按钮 2.4 +- 微雪电子 ESP32-S3-Touch-AMOLED-1.8 +- LILYGO T-Circle-S3 +- 虾哥 Mini C3 +- 璀璨·AI 吊坠 +- 无名科技 Nologo-星智-1.54TFT +- SenseCAP Watcher +- ESP-HI 超低成本机器狗 + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +## 软件 + +### 固件烧录 + +新手第一次操作建议先不要搭建开发环境,直接使用免开发环境烧录的固件。 + +固件默认接入 [xiaozhi.me](https://xiaozhi.me) 官方服务器,个人用户注册账号可以免费使用 Qwen 实时模型。 + +👉 [新手烧录固件教程](https://ccnphfhqs21z.feishu.cn/wiki/Zpz4wXBtdimBrLk25WdcXzxcnNS) + +### 开发环境 + +- Cursor 或 VSCode +- 安装 ESP-IDF 插件,选择 SDK 版本 5.4 或以上 +- Linux 比 Windows 更好,编译速度快,也免去驱动问题的困扰 +- 本项目使用 Google C++ 代码风格,提交代码时请确保符合规范 + +### 开发者文档 + +- [自定义开发板指南](docs/custom-board.md) - 学习如何为小智 AI 创建自定义开发板 +- [MCP 协议物联网控制用法说明](docs/mcp-usage.md) - 了解如何通过 MCP 协议控制物联网设备 +- [MCP 协议交互流程](docs/mcp-protocol.md) - 设备端 MCP 协议的实现方式 +- [MQTT + UDP 混合通信协议文档](docs/mqtt-udp.md) +- [一份详细的 WebSocket 通信协议文档](docs/websocket.md) + +## 大模型配置 + +如果你已经拥有一个小智 AI 聊天机器人设备,并且已接入官方服务器,可以登录 [xiaozhi.me](https://xiaozhi.me) 控制台进行配置。 + +👉 [后台操作视频教程(旧版界面)](https://www.bilibili.com/video/BV1jUCUY2EKM/) + +## 相关开源项目 + +在个人电脑上部署服务器,可以参考以下第三方开源的项目: + +- [xinnan-tech/xiaozhi-esp32-server](https://github.com/xinnan-tech/xiaozhi-esp32-server) Python 服务器 +- [joey-zhou/xiaozhi-esp32-server-java](https://github.com/joey-zhou/xiaozhi-esp32-server-java) Java 服务器 +- [AnimeAIChat/xiaozhi-server-go](https://github.com/AnimeAIChat/xiaozhi-server-go) Golang 服务器 + +使用小智通信协议的第三方客户端项目: + +- [huangjunsen0406/py-xiaozhi](https://github.com/huangjunsen0406/py-xiaozhi) Python 客户端 +- [TOM88812/xiaozhi-android-client](https://github.com/TOM88812/xiaozhi-android-client) Android 客户端 +- [100askTeam/xiaozhi-linux](http://github.com/100askTeam/xiaozhi-linux) 百问科技提供的 Linux 客户端 +- [78/xiaozhi-sf32](https://github.com/78/xiaozhi-sf32) 思澈科技的蓝牙芯片固件 +- [QuecPython/solution-xiaozhiAI](https://github.com/QuecPython/solution-xiaozhiAI) 移远提供的 QuecPython 固件 + +## 关于项目 + +这是一个由虾哥开源的 ESP32 项目,以 MIT 许可证发布,允许任何人免费使用,修改或用于商业用途。 + +我们希望通过这个项目,能够帮助大家了解 AI 硬件开发,将当下飞速发展的大语言模型应用到实际的硬件设备中。 + +如果你有任何想法或建议,请随时提出 Issues 或加入 QQ 群:1011329060 + +## Star History + + + + + + Star History Chart + + diff --git a/RP2040/animation.py b/RP2040/animation.py new file mode 100644 index 0000000..37e8233 --- /dev/null +++ b/RP2040/animation.py @@ -0,0 +1,267 @@ +from servoclass import Servo +import time + +current_pose = "pose_calibrate" +current_state = "state_startup" +animation_bool_a = False +animation_bool_b = False +last_toggle_a = time.ticks_ms() +last_toggle_b = time.ticks_ms() +new_state_flag = False + +servos = { + "YAW": Servo(pin_num=6, max_speed=400, max_accel=100, min_angle=10, max_angle=170), #Base Yaw Rotation + "ROL": Servo(pin_num=7, max_speed=600, max_accel=400, min_angle=30, max_angle=120), #Neck Roll + "PIT": Servo(pin_num=8, max_speed=600, max_accel=400, min_angle=1, max_angle=80), #Neck Pitch + "MOU": Servo(pin_num=9, max_speed=50000, max_accel=10000, min_angle=5, max_angle=150), #Mouth + "EYL": Servo(pin_num=12, max_speed=200, max_accel=10000, min_angle=30, max_angle=150), #Left Eyeball + "EYR": Servo(pin_num=13, max_speed=250, max_accel=10000, min_angle=30, max_angle=150), #Right Eyeball + "LID": Servo(pin_num=14, max_speed=50000, max_accel=50000, min_angle=30, max_angle=160), #EyeLid + "EAL": Servo(pin_num=15, max_speed=250, max_accel=200, min_angle=60, max_angle=150), #Left Ear + "EAR": Servo(pin_num=16, max_speed=500, max_accel=200, min_angle=30, max_angle=120), #Right Ear +} + +def apply_pose(pose): + pose = pose_map.get(pose, pose_calibrate) + for name, angle in pose.items(): + if name in servos: + servos[name].set_target(angle) + +def apply_state(state_name): + state_func = state_map.get(state_name) + if state_func: + state_func() # Call the function + else: + print(f"Unknown state: {state_name}") + +#_________________# Poses (static servo positions used in states) #_________________# + +pose_calibrate = { # Each dictionary key = servo name, value = angle + "YAW": 90, + "ROL": 90, + "PIT": 80, + "MOU": 170, + "LID": 110, + "EYL": 90, + "EYR": 90, + "EAL": 90, + "EAR": 90, +} +pose_sleep = { # Each dictionary key = servo name, value = angle +# "YAW": 88, +# "RWH": 89, + "ROL": 90, + "PIT": 80, + "MOU": 170, + "LID": 30, +# "EYL": 90, +# "EYR": 90, + "EAL": 150, + "EAR": 30, +} + +pose_base = { # Each dictionary key = servo name, value = angle +# "YAW": 88, +# "RWH": 89, + "ROL": 90, +# "PIT": 20, +# "MOU": 170, + "LID": 150, +# "EYL": 90, +# "EYR": 90, + "EAL": 130, + "EAR": 70, +} + +pose_speaking = { # Each dictionary key = servo name, value = angle +# "YAW": 88, +# "RWH": 89, +# "ROL": 90, +# "PIT": 20, + "MOU": 10, +# "LID": 130, +# "EYL": 90, +# "EYR": 90, + "EAL": 130, + "EAR": 70, +} + +pose_stop_speaking = { # Each dictionary key = servo name, value = angle +# "YAW": 88, +# "RWH": 89, +# "ROL": 90, +# "PIT": 20, + "MOU": 150, +# "LID": 130, +# "EYL": 90, +# "EYR": 90, + "EAL": 130, + "EAR": 70, +} + +pose_thinking_1 = { # Each dictionary key = servo name, value = angle +# "YAW": 90, +# "RWH": 90, + "ROL": 130, +# "PIT": 50, + "MOU": 150, + "LID": 70, +# "EYL": 90, +# "EYR": 90, + "EAL": 150, + "EAR": 120, +} + +pose_curious_2 = { # Each dictionary key = servo name, value = angle +# "YAW": 90, +# "RWH": 90, + "ROL": 40, +# "PIT": 10, + "MOU": 160, + "LID": 130, +# "EYL": 90, +# "EYR": 90, + "EAL": 60, + "EAR": 60, +} + +pose_map={ + "pose_calibrate": pose_calibrate, + "pose_base": pose_base, + "pose_thinking_1": pose_thinking_1, + "pose_curious_2": pose_curious_2, + "pose_sleep": pose_sleep, + "pose_speaking": pose_speaking, + "pose_stop_speaking": pose_stop_speaking, +} + +#_________________# #_________________# + +#_________________# States (Mix of poses + animations) #_________________# + + + +def state_startup(): + global new_state_flag + if new_state_flag == True: + apply_pose("pose_calibrate") + new_state_flag = False + +def state_sleep(): + global new_state_flag + if new_state_flag == True: + apply_pose("pose_sleep") + new_state_flag = False + +def state_speaking(): + global new_state_flag + if new_state_flag == True: + apply_pose("pose_speaking") + new_state_flag = False + +def state_thinking(): + now=time.ticks_ms() + global animation_bool_a, last_toggle_a, animation_bool_b, last_toggle_b, new_state_flag + if new_state_flag == True: + apply_pose("pose_base") + new_state_flag = False + if animation_bool_a == False: + servos["PIT"].set_target(50) + if animation_bool_a == True: + servos["PIT"].set_target(120) + if time.ticks_diff(now, last_toggle_a) >= 700: + animation_bool_a = not animation_bool_a # flip the boolean + last_toggle_a = now + + +def state_listen(): + global new_state_flag + if new_state_flag == True: + apply_pose("pose_curious_2") + new_state_flag = False + +def state_neutral(): + global new_state_flag + if new_state_flag == True: + apply_pose("pose_stop_speaking") + new_state_flag = False + +def state_happy(): + now=time.ticks_ms() + global animation_bool_a, last_toggle_a, animation_bool_b, last_toggle_b, new_state_flag + if new_state_flag == True: + apply_pose("pose_base") + new_state_flag = False +# print("idle") + if animation_bool_a == False: + servos["ROL"].set_target(70) + if animation_bool_a == True: + servos["ROL"].set_target(110) + if time.ticks_diff(now, last_toggle_a) >= 2000: + animation_bool_a = not animation_bool_a # flip the boolean + last_toggle_a = now + + if animation_bool_b == False: + servos["EAL"].set_target(100) + servos["EAR"].set_target(60) + if animation_bool_b == True: + servos["EAL"].set_target(160) + servos["EAR"].set_target(120) + if time.ticks_diff(now, last_toggle_b) >= 1000: + animation_bool_b = not animation_bool_b # flip the boolean + last_toggle_b = now +# print("Toggled:", animation_bool_a) + +def state_limber_up(): + now=time.ticks_ms() + global animation_bool_a, last_toggle_a, animation_bool_b, last_toggle_b, new_state_flag + if new_state_flag == True: + apply_pose("pose_base") + new_state_flag = False +# print("idle") + if animation_bool_a == False: +# servos["YAW"].set_target(50) + servos["ROL"].set_target(70) + servos["PIT"].set_target(70) + servos["EAL"].set_target(100) + servos["EYL"].set_target(60) + servos["MOU"].set_target(20) + servos["LID"].set_target(20) + servos["EYR"].set_target(60) + servos["EAL"].set_target(60) + servos["EAR"].set_target(60) + if animation_bool_a == True: +# servos["YAW"].set_target(130) + servos["ROL"].set_target(110) + servos["PIT"].set_target(5) + servos["EAL"].set_target(160) + servos["EYL"].set_target(120) + servos["MOU"].set_target(160) + servos["LID"].set_target(160) + servos["EYR"].set_target(120) + servos["EAL"].set_target(120) + servos["EAR"].set_target(120) + if time.ticks_diff(now, last_toggle_a) >= 1000: + animation_bool_a = not animation_bool_a # flip the boolean + last_toggle_a = now + +# Note: system states: +# - idle: sleeping, wakeword not initiated listening mode +# - neutral: between finished speaking and begun listening. potentially use as marker for end of speech +# - listening +# - speaking + +state_map={ + "neutral": state_neutral, + "idle": state_sleep, + "listening": state_listen, + "state_startup": state_startup, + "thinking": state_thinking, + "speaking": state_speaking, + "state_limber_up": state_limber_up, + "happy": state_happy +} + +#_________________# #_________________# + + diff --git a/RP2040/main.py b/RP2040/main.py new file mode 100644 index 0000000..8d6d914 --- /dev/null +++ b/RP2040/main.py @@ -0,0 +1,86 @@ +# motion_servo.py (MicroPython for RP2040) +from machine import Pin, PWM, UART +import time, random +import urandom +from servoclass import Servo +import sys, select, uselect +import math +import animation +from animation import servos + +ESP = UART(1, baudrate=115200, tx=Pin(4), rx=Pin(5)) +rx_buffer = b"" + +mode = Pin(20, Pin.IN, Pin.PULL_UP) + +# track direction for each servo (1 = going to max, -1 = going to min) +directions = {name: 1 for name in servos.keys()} + +last_time = time.ticks_ms() +last_switch = last_time + +# servos["YAW"].set_target(88) +# # servos["RWH"].set_target(89) + + +while True: + now = time.ticks_ms() + dt = time.ticks_diff(now, last_time) / 1000.0 + last_time = now + +# # check if blink should finish +# update_blink(servos, now, lid="LID") + + if ESP.any(): + rx_buffer += ESP.read() # bytes + bytes = OK + while b"\n" in rx_buffer: + line, rx_buffer = rx_buffer.split(b"\n", 1) + rcvstate = line.decode().strip() + print("RX:", rcvstate) + if rcvstate in animation.state_map: + print("applying ", end="") + print(rcvstate) + animation.new_state_flag = True + animation.current_state = rcvstate + + +# if (mode.value() == 0): +# animation.apply_state("state_limber_up") + + if (mode.value() == 1): + animation.apply_pose("pose_calibrate") + + animation.apply_state(animation.current_state) + + for s in servos.values(): + s.update(dt) + time.sleep_ms(1) + +# # EXAMPLE: randomly trigger a blink +# if not blink_state["active"] and (random.randint(0, 1000)<1): +# trigger_blink(servos, now, closed_angle=30, lid="LID") + +# blink_state = { +# "active": False, +# "start_time": 0, +# "duration": 150, # ms lids stay closed +# "original_pos": None, +# } +# +# +# +# def trigger_blink(servos, now, closed_angle=30, lid="LID"): +# if blink_state["active"]: +# return # already blinking, ignore +# s = servos["LID"] +# blink_state["active"] = True +# blink_state["start_time"] = now +# blink_state["original_pos"] = s.target # remember current target +# s.set_target(s.min_angle) # snap to closed target +# +# def update_blink(servos, now, lid="LID"): +# if blink_state["active"]: +# if time.ticks_diff(now, blink_state["start_time"]) > blink_state["duration"]: +# s = servos[lid] +# s.set_target(blink_state["original_pos"]) # restore old target +# blink_state["active"] = False diff --git a/RP2040/servoclass.py b/RP2040/servoclass.py new file mode 100644 index 0000000..88bfd58 --- /dev/null +++ b/RP2040/servoclass.py @@ -0,0 +1,109 @@ +from machine import Pin, PWM +import time, random +import urandom + +def clamp(x, a, b): + return a if x < a else (b if x > b else x) + +class Servo: + def __init__(self, pin_num, max_speed=120.0, max_accel=360.0, min_angle=0.0, max_angle=180.0, enabled=True): + self.pwm = PWM(Pin(pin_num)) + self.pwm.freq(50) + + # motion state + self.pos = 90.0 + self.vel = 0.0 + self.target = 90.0 + + # tuning + self.max_speed = float(max_speed) + self.max_accel = float(max_accel) + + # limits + self.min_angle = float(min_angle) + self.max_angle = float(max_angle) + + # tolerances + self.pos_tolerance = 0.6 + self.vel_tolerance = 1.0 + + # debug flag + self.enabled = enabled + + self._write_pwm(self.pos) + + def set_target(self, angle): + # clamp target to servo’s declared limits + self.target = clamp(float(angle), self.min_angle, self.max_angle) + + def update(self, dt): + if not self.enabled: + return + if dt <= 0: + return + + error = self.target - self.pos + dist = abs(error) + # direction we need to move to reduce error + desired_dir = 0 if dist < 1e-9 else (1.0 if error > 0 else -1.0) + # current velocity sign + if abs(self.vel) < 1e-9: + vel_dir = 0.0 + else: + vel_dir = 1.0 if self.vel > 0 else -1.0 + + # small-target case: if we're close & nearly stopped, snap cleanly + if dist <= self.pos_tolerance and abs(self.vel) <= self.vel_tolerance: + self.pos = self.target + self.vel = 0.0 + self._write_pwm(self.pos) + return + + # braking-first rule: if we're moving opposite desired direction, brake + if vel_dir != 0 and desired_dir != 0 and vel_dir != desired_dir: + # apply maximum braking (opposite current velocity) + accel = -vel_dir * self.max_accel + else: + # else decide accelerate or start decelerating so we stop exactly at target + stopping_dist = (self.vel * self.vel) / (2.0 * self.max_accel) # always >= 0 + if dist > stopping_dist: + # still room to accelerate toward the target + accel = desired_dir * self.max_accel + else: + # we must decelerate to stop at the target + accel = -desired_dir * self.max_accel + + # integrate velocity + new_vel = self.vel + accel * dt + + # avoid sign flip jitter: if braking would cross zero in this step, clamp to zero + if self.vel > 0 and new_vel < 0: + new_vel = 0.0 + elif self.vel < 0 and new_vel > 0: + new_vel = 0.0 + + # clamp speed to limits + new_vel = clamp(new_vel, -self.max_speed, self.max_speed) + + # integrate position + self.vel = new_vel + self.pos = self.pos + self.vel * dt + + # clamp position to valid servo range (avoid writing out-of-bounds) + self.pos = clamp(self.pos, 0.0, 180.0) + + # final small-check: if we are extremely close, snap to target to avoid tiny oscillation +# if abs(self.target - self.pos) <= self.pos_tolerance and abs(self.vel) <= self.vel_tolerance: +# self.pos = self.target +# self.vel = 0.0 + + self._write_pwm(self.pos) + + def _write_pwm(self, angle): + # map 0..180 -> 500..2500 us pulse width (20 ms period) + min_us = 500.0 + max_us = 2500.0 + us = min_us + (max_us - min_us) * (angle / 180.0) + # convert to 16-bit duty for 20 ms period + duty = int(us * 65535.0 / 20000.0) + self.pwm.duty_u16(duty) diff --git a/docs/CogNogV1_0.pdf b/docs/CogNogV1_0.pdf new file mode 100644 index 0000000..e140f1a --- /dev/null +++ b/docs/CogNogV1_0.pdf @@ -0,0 +1,37225 @@ +%PDF-1.4 +%߬ +3 0 obj +<> +endobj +4 0 obj +<< +/Length 445193 +>> +stream +0.14 w +0 G +q +2 J +0 j +72 M +1.00 g +[] 0 d +0.00 816.83 1397.93 -816.83 re +f +0.60 g +494.64 108.00 m 494.64 108.80 494.00 109.44 493.20 109.44 c +492.40 109.44 491.76 108.80 491.76 108.00 c +491.76 107.20 492.40 106.56 493.20 106.56 c +494.00 106.56 494.64 107.20 494.64 108.00 c +f +0.60 g +1027.44 489.60 m 1027.44 490.40 1026.80 491.04 1026.00 491.04 c +1025.20 491.04 1024.56 490.40 1024.56 489.60 c +1024.56 488.80 1025.20 488.16 1026.00 488.16 c +1026.80 488.16 1027.44 488.80 1027.44 489.60 c +f +0.60 g +1027.44 482.40 m 1027.44 483.20 1026.80 483.84 1026.00 483.84 c +1025.20 483.84 1024.56 483.20 1024.56 482.40 c +1024.56 481.60 1025.20 480.96 1026.00 480.96 c +1026.80 480.96 1027.44 481.60 1027.44 482.40 c +f +0.60 g +1160.64 489.60 m 1160.64 490.40 1160.00 491.04 1159.20 491.04 c +1158.40 491.04 1157.76 490.40 1157.76 489.60 c +1157.76 488.80 1158.40 488.16 1159.20 488.16 c +1160.00 488.16 1160.64 488.80 1160.64 489.60 c +f +0.60 g +1164.24 482.40 m 1164.24 483.20 1163.60 483.84 1162.80 483.84 c +1162.00 483.84 1161.36 483.20 1161.36 482.40 c +1161.36 481.60 1162.00 480.96 1162.80 480.96 c +1163.60 480.96 1164.24 481.60 1164.24 482.40 c +f +0.60 g +1160.64 475.20 m 1160.64 476.00 1160.00 476.64 1159.20 476.64 c +1158.40 476.64 1157.76 476.00 1157.76 475.20 c +1157.76 474.40 1158.40 473.76 1159.20 473.76 c +1160.00 473.76 1160.64 474.40 1160.64 475.20 c +f +0.60 g +1031.04 468.00 m 1031.04 468.80 1030.40 469.44 1029.60 469.44 c +1028.80 469.44 1028.16 468.80 1028.16 468.00 c +1028.16 467.20 1028.80 466.56 1029.60 466.56 c +1030.40 466.56 1031.04 467.20 1031.04 468.00 c +f +0.60 g +663.84 460.80 m 663.84 461.60 663.20 462.24 662.40 462.24 c +661.60 462.24 660.96 461.60 660.96 460.80 c +660.96 460.00 661.60 459.36 662.40 459.36 c +663.20 459.36 663.84 460.00 663.84 460.80 c +f +0.60 g +663.84 453.60 m 663.84 454.40 663.20 455.04 662.40 455.04 c +661.60 455.04 660.96 454.40 660.96 453.60 c +660.96 452.80 661.60 452.16 662.40 452.16 c +663.20 452.16 663.84 452.80 663.84 453.60 c +f +0.60 g +656.64 640.80 m 656.64 641.60 656.00 642.24 655.20 642.24 c +654.40 642.24 653.76 641.60 653.76 640.80 c +653.76 640.00 654.40 639.36 655.20 639.36 c +656.00 639.36 656.64 640.00 656.64 640.80 c +f +0.60 g +656.64 630.00 m 656.64 630.80 656.00 631.44 655.20 631.44 c +654.40 631.44 653.76 630.80 653.76 630.00 c +653.76 629.20 654.40 628.56 655.20 628.56 c +656.00 628.56 656.64 629.20 656.64 630.00 c +f +0.60 g +656.64 622.80 m 656.64 623.60 656.00 624.24 655.20 624.24 c +654.40 624.24 653.76 623.60 653.76 622.80 c +653.76 622.00 654.40 621.36 655.20 621.36 c +656.00 621.36 656.64 622.00 656.64 622.80 c +f +0.60 g +656.64 615.60 m 656.64 616.40 656.00 617.04 655.20 617.04 c +654.40 617.04 653.76 616.40 653.76 615.60 c +653.76 614.80 654.40 614.16 655.20 614.16 c +656.00 614.16 656.64 614.80 656.64 615.60 c +f +0.60 g +656.64 608.40 m 656.64 609.20 656.00 609.84 655.20 609.84 c +654.40 609.84 653.76 609.20 653.76 608.40 c +653.76 607.60 654.40 606.96 655.20 606.96 c +656.00 606.96 656.64 607.60 656.64 608.40 c +f +0.60 g +656.64 597.60 m 656.64 598.40 656.00 599.04 655.20 599.04 c +654.40 599.04 653.76 598.40 653.76 597.60 c +653.76 596.80 654.40 596.16 655.20 596.16 c +656.00 596.16 656.64 596.80 656.64 597.60 c +f +0.60 g +912.24 644.40 m 912.24 645.20 911.60 645.84 910.80 645.84 c +910.00 645.84 909.36 645.20 909.36 644.40 c +909.36 643.60 910.00 642.96 910.80 642.96 c +911.60 642.96 912.24 643.60 912.24 644.40 c +f +0.60 g +912.24 637.20 m 912.24 638.00 911.60 638.64 910.80 638.64 c +910.00 638.64 909.36 638.00 909.36 637.20 c +909.36 636.40 910.00 635.76 910.80 635.76 c +911.60 635.76 912.24 636.40 912.24 637.20 c +f +0.60 g +912.24 630.00 m 912.24 630.80 911.60 631.44 910.80 631.44 c +910.00 631.44 909.36 630.80 909.36 630.00 c +909.36 629.20 910.00 628.56 910.80 628.56 c +911.60 628.56 912.24 629.20 912.24 630.00 c +f +0.60 g +912.24 622.80 m 912.24 623.60 911.60 624.24 910.80 624.24 c +910.00 624.24 909.36 623.60 909.36 622.80 c +909.36 622.00 910.00 621.36 910.80 621.36 c +911.60 621.36 912.24 622.00 912.24 622.80 c +f +0.60 g +912.24 565.20 m 912.24 566.00 911.60 566.64 910.80 566.64 c +910.00 566.64 909.36 566.00 909.36 565.20 c +909.36 564.40 910.00 563.76 910.80 563.76 c +911.60 563.76 912.24 564.40 912.24 565.20 c +f +0.60 g +912.24 558.00 m 912.24 558.80 911.60 559.44 910.80 559.44 c +910.00 559.44 909.36 558.80 909.36 558.00 c +909.36 557.20 910.00 556.56 910.80 556.56 c +911.60 556.56 912.24 557.20 912.24 558.00 c +f +0.60 g +912.24 550.80 m 912.24 551.60 911.60 552.24 910.80 552.24 c +910.00 552.24 909.36 551.60 909.36 550.80 c +909.36 550.00 910.00 549.36 910.80 549.36 c +911.60 549.36 912.24 550.00 912.24 550.80 c +f +0.60 g +912.24 543.60 m 912.24 544.40 911.60 545.04 910.80 545.04 c +910.00 545.04 909.36 544.40 909.36 543.60 c +909.36 542.80 910.00 542.16 910.80 542.16 c +911.60 542.16 912.24 542.80 912.24 543.60 c +f +0.60 g +912.24 536.40 m 912.24 537.20 911.60 537.84 910.80 537.84 c +910.00 537.84 909.36 537.20 909.36 536.40 c +909.36 535.60 910.00 534.96 910.80 534.96 c +911.60 534.96 912.24 535.60 912.24 536.40 c +f +0.60 g +912.24 529.20 m 912.24 530.00 911.60 530.64 910.80 530.64 c +910.00 530.64 909.36 530.00 909.36 529.20 c +909.36 528.40 910.00 527.76 910.80 527.76 c +911.60 527.76 912.24 528.40 912.24 529.20 c +f +0.60 g +912.24 522.00 m 912.24 522.80 911.60 523.44 910.80 523.44 c +910.00 523.44 909.36 522.80 909.36 522.00 c +909.36 521.20 910.00 520.56 910.80 520.56 c +911.60 520.56 912.24 521.20 912.24 522.00 c +f +0.60 g +912.24 514.80 m 912.24 515.60 911.60 516.24 910.80 516.24 c +910.00 516.24 909.36 515.60 909.36 514.80 c +909.36 514.00 910.00 513.36 910.80 513.36 c +911.60 513.36 912.24 514.00 912.24 514.80 c +f +0.60 g +912.24 507.60 m 912.24 508.40 911.60 509.04 910.80 509.04 c +910.00 509.04 909.36 508.40 909.36 507.60 c +909.36 506.80 910.00 506.16 910.80 506.16 c +911.60 506.16 912.24 506.80 912.24 507.60 c +f +0.60 g +912.24 500.40 m 912.24 501.20 911.60 501.84 910.80 501.84 c +910.00 501.84 909.36 501.20 909.36 500.40 c +909.36 499.60 910.00 498.96 910.80 498.96 c +911.60 498.96 912.24 499.60 912.24 500.40 c +f +0.60 g +912.24 493.20 m 912.24 494.00 911.60 494.64 910.80 494.64 c +910.00 494.64 909.36 494.00 909.36 493.20 c +909.36 492.40 910.00 491.76 910.80 491.76 c +911.60 491.76 912.24 492.40 912.24 493.20 c +f +0.60 g +912.24 486.00 m 912.24 486.80 911.60 487.44 910.80 487.44 c +910.00 487.44 909.36 486.80 909.36 486.00 c +909.36 485.20 910.00 484.56 910.80 484.56 c +911.60 484.56 912.24 485.20 912.24 486.00 c +f +0.60 g +901.44 450.00 m 901.44 450.80 900.80 451.44 900.00 451.44 c +899.20 451.44 898.56 450.80 898.56 450.00 c +898.56 449.20 899.20 448.56 900.00 448.56 c +900.80 448.56 901.44 449.20 901.44 450.00 c +f +0.60 g +901.44 442.80 m 901.44 443.60 900.80 444.24 900.00 444.24 c +899.20 444.24 898.56 443.60 898.56 442.80 c +898.56 442.00 899.20 441.36 900.00 441.36 c +900.80 441.36 901.44 442.00 901.44 442.80 c +f +0.60 g +901.44 435.60 m 901.44 436.40 900.80 437.04 900.00 437.04 c +899.20 437.04 898.56 436.40 898.56 435.60 c +898.56 434.80 899.20 434.16 900.00 434.16 c +900.80 434.16 901.44 434.80 901.44 435.60 c +f +0.60 g +923.04 673.20 m 923.04 674.00 922.40 674.64 921.60 674.64 c +920.80 674.64 920.16 674.00 920.16 673.20 c +920.16 672.40 920.80 671.76 921.60 671.76 c +922.40 671.76 923.04 672.40 923.04 673.20 c +f +0.60 g +923.04 666.00 m 923.04 666.80 922.40 667.44 921.60 667.44 c +920.80 667.44 920.16 666.80 920.16 666.00 c +920.16 665.20 920.80 664.56 921.60 664.56 c +922.40 664.56 923.04 665.20 923.04 666.00 c +f +0.60 g +912.24 572.40 m 912.24 573.20 911.60 573.84 910.80 573.84 c +910.00 573.84 909.36 573.20 909.36 572.40 c +909.36 571.60 910.00 570.96 910.80 570.96 c +911.60 570.96 912.24 571.60 912.24 572.40 c +f +0.60 g +1110.24 709.20 m 1110.24 710.00 1109.60 710.64 1108.80 710.64 c +1108.00 710.64 1107.36 710.00 1107.36 709.20 c +1107.36 708.40 1108.00 707.76 1108.80 707.76 c +1109.60 707.76 1110.24 708.40 1110.24 709.20 c +f +0.60 g +1110.24 716.40 m 1110.24 717.20 1109.60 717.84 1108.80 717.84 c +1108.00 717.84 1107.36 717.20 1107.36 716.40 c +1107.36 715.60 1108.00 714.96 1108.80 714.96 c +1109.60 714.96 1110.24 715.60 1110.24 716.40 c +f +0.60 g +145.44 669.60 m 145.44 670.40 144.80 671.04 144.00 671.04 c +143.20 671.04 142.56 670.40 142.56 669.60 c +142.56 668.80 143.20 668.16 144.00 668.16 c +144.80 668.16 145.44 668.80 145.44 669.60 c +f +0.60 g +145.44 662.40 m 145.44 663.20 144.80 663.84 144.00 663.84 c +143.20 663.84 142.56 663.20 142.56 662.40 c +142.56 661.60 143.20 660.96 144.00 660.96 c +144.80 660.96 145.44 661.60 145.44 662.40 c +f +0.60 g +145.44 655.20 m 145.44 656.00 144.80 656.64 144.00 656.64 c +143.20 656.64 142.56 656.00 142.56 655.20 c +142.56 654.40 143.20 653.76 144.00 653.76 c +144.80 653.76 145.44 654.40 145.44 655.20 c +f +0.60 g +145.44 648.00 m 145.44 648.80 144.80 649.44 144.00 649.44 c +143.20 649.44 142.56 648.80 142.56 648.00 c +142.56 647.20 143.20 646.56 144.00 646.56 c +144.80 646.56 145.44 647.20 145.44 648.00 c +f +0.60 g +145.44 640.80 m 145.44 641.60 144.80 642.24 144.00 642.24 c +143.20 642.24 142.56 641.60 142.56 640.80 c +142.56 640.00 143.20 639.36 144.00 639.36 c +144.80 639.36 145.44 640.00 145.44 640.80 c +f +0.60 g +145.44 633.60 m 145.44 634.40 144.80 635.04 144.00 635.04 c +143.20 635.04 142.56 634.40 142.56 633.60 c +142.56 632.80 143.20 632.16 144.00 632.16 c +144.80 632.16 145.44 632.80 145.44 633.60 c +f +0.60 g +145.44 626.40 m 145.44 627.20 144.80 627.84 144.00 627.84 c +143.20 627.84 142.56 627.20 142.56 626.40 c +142.56 625.60 143.20 624.96 144.00 624.96 c +144.80 624.96 145.44 625.60 145.44 626.40 c +f +0.60 g +145.44 619.20 m 145.44 620.00 144.80 620.64 144.00 620.64 c +143.20 620.64 142.56 620.00 142.56 619.20 c +142.56 618.40 143.20 617.76 144.00 617.76 c +144.80 617.76 145.44 618.40 145.44 619.20 c +f +0.60 g +134.64 612.00 m 134.64 612.80 134.00 613.44 133.20 613.44 c +132.40 613.44 131.76 612.80 131.76 612.00 c +131.76 611.20 132.40 610.56 133.20 610.56 c +134.00 610.56 134.64 611.20 134.64 612.00 c +f +0.60 g +134.64 604.80 m 134.64 605.60 134.00 606.24 133.20 606.24 c +132.40 606.24 131.76 605.60 131.76 604.80 c +131.76 604.00 132.40 603.36 133.20 603.36 c +134.00 603.36 134.64 604.00 134.64 604.80 c +f +0.60 g +145.44 597.60 m 145.44 598.40 144.80 599.04 144.00 599.04 c +143.20 599.04 142.56 598.40 142.56 597.60 c +142.56 596.80 143.20 596.16 144.00 596.16 c +144.80 596.16 145.44 596.80 145.44 597.60 c +f +0.60 g +145.44 590.40 m 145.44 591.20 144.80 591.84 144.00 591.84 c +143.20 591.84 142.56 591.20 142.56 590.40 c +142.56 589.60 143.20 588.96 144.00 588.96 c +144.80 588.96 145.44 589.60 145.44 590.40 c +f +0.60 g +145.44 583.20 m 145.44 584.00 144.80 584.64 144.00 584.64 c +143.20 584.64 142.56 584.00 142.56 583.20 c +142.56 582.40 143.20 581.76 144.00 581.76 c +144.80 581.76 145.44 582.40 145.44 583.20 c +f +0.60 g +203.04 507.60 m 203.04 508.40 202.40 509.04 201.60 509.04 c +200.80 509.04 200.16 508.40 200.16 507.60 c +200.16 506.80 200.80 506.16 201.60 506.16 c +202.40 506.16 203.04 506.80 203.04 507.60 c +f +0.60 g +217.44 507.60 m 217.44 508.40 216.80 509.04 216.00 509.04 c +215.20 509.04 214.56 508.40 214.56 507.60 c +214.56 506.80 215.20 506.16 216.00 506.16 c +216.80 506.16 217.44 506.80 217.44 507.60 c +f +0.60 g +210.24 507.60 m 210.24 508.40 209.60 509.04 208.80 509.04 c +208.00 509.04 207.36 508.40 207.36 507.60 c +207.36 506.80 208.00 506.16 208.80 506.16 c +209.60 506.16 210.24 506.80 210.24 507.60 c +f +0.60 g +224.64 507.60 m 224.64 508.40 224.00 509.04 223.20 509.04 c +222.40 509.04 221.76 508.40 221.76 507.60 c +221.76 506.80 222.40 506.16 223.20 506.16 c +224.00 506.16 224.64 506.80 224.64 507.60 c +f +0.60 g +231.84 507.60 m 231.84 508.40 231.20 509.04 230.40 509.04 c +229.60 509.04 228.96 508.40 228.96 507.60 c +228.96 506.80 229.60 506.16 230.40 506.16 c +231.20 506.16 231.84 506.80 231.84 507.60 c +f +0.60 g +239.04 507.60 m 239.04 508.40 238.40 509.04 237.60 509.04 c +236.80 509.04 236.16 508.40 236.16 507.60 c +236.16 506.80 236.80 506.16 237.60 506.16 c +238.40 506.16 239.04 506.80 239.04 507.60 c +f +0.60 g +246.24 507.60 m 246.24 508.40 245.60 509.04 244.80 509.04 c +244.00 509.04 243.36 508.40 243.36 507.60 c +243.36 506.80 244.00 506.16 244.80 506.16 c +245.60 506.16 246.24 506.80 246.24 507.60 c +f +0.60 g +253.44 507.60 m 253.44 508.40 252.80 509.04 252.00 509.04 c +251.20 509.04 250.56 508.40 250.56 507.60 c +250.56 506.80 251.20 506.16 252.00 506.16 c +252.80 506.16 253.44 506.80 253.44 507.60 c +f +0.60 g +260.64 507.60 m 260.64 508.40 260.00 509.04 259.20 509.04 c +258.40 509.04 257.76 508.40 257.76 507.60 c +257.76 506.80 258.40 506.16 259.20 506.16 c +260.00 506.16 260.64 506.80 260.64 507.60 c +f +0.60 g +267.84 507.60 m 267.84 508.40 267.20 509.04 266.40 509.04 c +265.60 509.04 264.96 508.40 264.96 507.60 c +264.96 506.80 265.60 506.16 266.40 506.16 c +267.20 506.16 267.84 506.80 267.84 507.60 c +f +0.60 g +275.04 507.60 m 275.04 508.40 274.40 509.04 273.60 509.04 c +272.80 509.04 272.16 508.40 272.16 507.60 c +272.16 506.80 272.80 506.16 273.60 506.16 c +274.40 506.16 275.04 506.80 275.04 507.60 c +f +0.60 g +282.24 507.60 m 282.24 508.40 281.60 509.04 280.80 509.04 c +280.00 509.04 279.36 508.40 279.36 507.60 c +279.36 506.80 280.00 506.16 280.80 506.16 c +281.60 506.16 282.24 506.80 282.24 507.60 c +f +0.60 g +339.84 676.80 m 339.84 677.60 339.20 678.24 338.40 678.24 c +337.60 678.24 336.96 677.60 336.96 676.80 c +336.96 676.00 337.60 675.36 338.40 675.36 c +339.20 675.36 339.84 676.00 339.84 676.80 c +f +0.60 g +339.84 669.60 m 339.84 670.40 339.20 671.04 338.40 671.04 c +337.60 671.04 336.96 670.40 336.96 669.60 c +336.96 668.80 337.60 668.16 338.40 668.16 c +339.20 668.16 339.84 668.80 339.84 669.60 c +f +0.60 g +339.84 662.40 m 339.84 663.20 339.20 663.84 338.40 663.84 c +337.60 663.84 336.96 663.20 336.96 662.40 c +336.96 661.60 337.60 660.96 338.40 660.96 c +339.20 660.96 339.84 661.60 339.84 662.40 c +f +0.60 g +339.84 655.20 m 339.84 656.00 339.20 656.64 338.40 656.64 c +337.60 656.64 336.96 656.00 336.96 655.20 c +336.96 654.40 337.60 653.76 338.40 653.76 c +339.20 653.76 339.84 654.40 339.84 655.20 c +f +0.60 g +339.84 648.00 m 339.84 648.80 339.20 649.44 338.40 649.44 c +337.60 649.44 336.96 648.80 336.96 648.00 c +336.96 647.20 337.60 646.56 338.40 646.56 c +339.20 646.56 339.84 647.20 339.84 648.00 c +f +0.60 g +339.84 640.80 m 339.84 641.60 339.20 642.24 338.40 642.24 c +337.60 642.24 336.96 641.60 336.96 640.80 c +336.96 640.00 337.60 639.36 338.40 639.36 c +339.20 639.36 339.84 640.00 339.84 640.80 c +f +0.60 g +339.84 633.60 m 339.84 634.40 339.20 635.04 338.40 635.04 c +337.60 635.04 336.96 634.40 336.96 633.60 c +336.96 632.80 337.60 632.16 338.40 632.16 c +339.20 632.16 339.84 632.80 339.84 633.60 c +f +0.60 g +339.84 626.40 m 339.84 627.20 339.20 627.84 338.40 627.84 c +337.60 627.84 336.96 627.20 336.96 626.40 c +336.96 625.60 337.60 624.96 338.40 624.96 c +339.20 624.96 339.84 625.60 339.84 626.40 c +f +0.60 g +339.84 619.20 m 339.84 620.00 339.20 620.64 338.40 620.64 c +337.60 620.64 336.96 620.00 336.96 619.20 c +336.96 618.40 337.60 617.76 338.40 617.76 c +339.20 617.76 339.84 618.40 339.84 619.20 c +f +0.60 g +339.84 612.00 m 339.84 612.80 339.20 613.44 338.40 613.44 c +337.60 613.44 336.96 612.80 336.96 612.00 c +336.96 611.20 337.60 610.56 338.40 610.56 c +339.20 610.56 339.84 611.20 339.84 612.00 c +f +0.60 g +339.84 604.80 m 339.84 605.60 339.20 606.24 338.40 606.24 c +337.60 606.24 336.96 605.60 336.96 604.80 c +336.96 604.00 337.60 603.36 338.40 603.36 c +339.20 603.36 339.84 604.00 339.84 604.80 c +f +0.60 g +339.84 597.60 m 339.84 598.40 339.20 599.04 338.40 599.04 c +337.60 599.04 336.96 598.40 336.96 597.60 c +336.96 596.80 337.60 596.16 338.40 596.16 c +339.20 596.16 339.84 596.80 339.84 597.60 c +f +0.60 g +339.84 590.40 m 339.84 591.20 339.20 591.84 338.40 591.84 c +337.60 591.84 336.96 591.20 336.96 590.40 c +336.96 589.60 337.60 588.96 338.40 588.96 c +339.20 588.96 339.84 589.60 339.84 590.40 c +f +0.60 g +339.84 583.20 m 339.84 584.00 339.20 584.64 338.40 584.64 c +337.60 584.64 336.96 584.00 336.96 583.20 c +336.96 582.40 337.60 581.76 338.40 581.76 c +339.20 581.76 339.84 582.40 339.84 583.20 c +f +0.60 g +537.84 734.40 m 537.84 735.20 537.20 735.84 536.40 735.84 c +535.60 735.84 534.96 735.20 534.96 734.40 c +534.96 733.60 535.60 732.96 536.40 732.96 c +537.20 732.96 537.84 733.60 537.84 734.40 c +f +0.60 g +595.44 730.80 m 595.44 731.60 594.80 732.24 594.00 732.24 c +593.20 732.24 592.56 731.60 592.56 730.80 c +592.56 730.00 593.20 729.36 594.00 729.36 c +594.80 729.36 595.44 730.00 595.44 730.80 c +f +0.60 g +566.64 763.20 m 566.64 764.00 566.00 764.64 565.20 764.64 c +564.40 764.64 563.76 764.00 563.76 763.20 c +563.76 762.40 564.40 761.76 565.20 761.76 c +566.00 761.76 566.64 762.40 566.64 763.20 c +f +0.60 g +501.84 615.60 m 501.84 616.40 501.20 617.04 500.40 617.04 c +499.60 617.04 498.96 616.40 498.96 615.60 c +498.96 614.80 499.60 614.16 500.40 614.16 c +501.20 614.16 501.84 614.80 501.84 615.60 c +f +0.60 g +559.44 532.80 m 559.44 533.60 558.80 534.24 558.00 534.24 c +557.20 534.24 556.56 533.60 556.56 532.80 c +556.56 532.00 557.20 531.36 558.00 531.36 c +558.80 531.36 559.44 532.00 559.44 532.80 c +f +0.60 g +199.44 388.80 m 199.44 389.60 198.80 390.24 198.00 390.24 c +197.20 390.24 196.56 389.60 196.56 388.80 c +196.56 388.00 197.20 387.36 198.00 387.36 c +198.80 387.36 199.44 388.00 199.44 388.80 c +f +0.60 g +199.44 381.60 m 199.44 382.40 198.80 383.04 198.00 383.04 c +197.20 383.04 196.56 382.40 196.56 381.60 c +196.56 380.80 197.20 380.16 198.00 380.16 c +198.80 380.16 199.44 380.80 199.44 381.60 c +f +0.60 g +51.84 374.40 m 51.84 375.20 51.20 375.84 50.40 375.84 c +49.60 375.84 48.96 375.20 48.96 374.40 c +48.96 373.60 49.60 372.96 50.40 372.96 c +51.20 372.96 51.84 373.60 51.84 374.40 c +f +0.60 g +51.84 381.60 m 51.84 382.40 51.20 383.04 50.40 383.04 c +49.60 383.04 48.96 382.40 48.96 381.60 c +48.96 380.80 49.60 380.16 50.40 380.16 c +51.20 380.16 51.84 380.80 51.84 381.60 c +f +0.60 g +51.84 388.80 m 51.84 389.60 51.20 390.24 50.40 390.24 c +49.60 390.24 48.96 389.60 48.96 388.80 c +48.96 388.00 49.60 387.36 50.40 387.36 c +51.20 387.36 51.84 388.00 51.84 388.80 c +f +0.60 g +51.84 396.00 m 51.84 396.80 51.20 397.44 50.40 397.44 c +49.60 397.44 48.96 396.80 48.96 396.00 c +48.96 395.20 49.60 394.56 50.40 394.56 c +51.20 394.56 51.84 395.20 51.84 396.00 c +f +0.60 g +66.24 432.00 m 66.24 432.80 65.60 433.44 64.80 433.44 c +64.00 433.44 63.36 432.80 63.36 432.00 c +63.36 431.20 64.00 430.56 64.80 430.56 c +65.60 430.56 66.24 431.20 66.24 432.00 c +f +0.60 g +66.24 439.20 m 66.24 440.00 65.60 440.64 64.80 440.64 c +64.00 440.64 63.36 440.00 63.36 439.20 c +63.36 438.40 64.00 437.76 64.80 437.76 c +65.60 437.76 66.24 438.40 66.24 439.20 c +f +0.60 g +195.84 450.00 m 195.84 450.80 195.20 451.44 194.40 451.44 c +193.60 451.44 192.96 450.80 192.96 450.00 c +192.96 449.20 193.60 448.56 194.40 448.56 c +195.20 448.56 195.84 449.20 195.84 450.00 c +f +0.60 g +253.44 385.20 m 253.44 386.00 252.80 386.64 252.00 386.64 c +251.20 386.64 250.56 386.00 250.56 385.20 c +250.56 384.40 251.20 383.76 252.00 383.76 c +252.80 383.76 253.44 384.40 253.44 385.20 c +f +0.60 g +253.44 453.60 m 253.44 454.40 252.80 455.04 252.00 455.04 c +251.20 455.04 250.56 454.40 250.56 453.60 c +250.56 452.80 251.20 452.16 252.00 452.16 c +252.80 452.16 253.44 452.80 253.44 453.60 c +f +0.60 g +563.04 468.00 m 563.04 468.80 562.40 469.44 561.60 469.44 c +560.80 469.44 560.16 468.80 560.16 468.00 c +560.16 467.20 560.80 466.56 561.60 466.56 c +562.40 466.56 563.04 467.20 563.04 468.00 c +f +0.60 g +221.04 259.20 m 221.04 260.00 220.40 260.64 219.60 260.64 c +218.80 260.64 218.16 260.00 218.16 259.20 c +218.16 258.40 218.80 257.76 219.60 257.76 c +220.40 257.76 221.04 258.40 221.04 259.20 c +f +0.60 g +221.04 273.60 m 221.04 274.40 220.40 275.04 219.60 275.04 c +218.80 275.04 218.16 274.40 218.16 273.60 c +218.16 272.80 218.80 272.16 219.60 272.16 c +220.40 272.16 221.04 272.80 221.04 273.60 c +f +0.60 g +221.04 280.80 m 221.04 281.60 220.40 282.24 219.60 282.24 c +218.80 282.24 218.16 281.60 218.16 280.80 c +218.16 280.00 218.80 279.36 219.60 279.36 c +220.40 279.36 221.04 280.00 221.04 280.80 c +f +0.60 g +131.04 320.40 m 131.04 321.20 130.40 321.84 129.60 321.84 c +128.80 321.84 128.16 321.20 128.16 320.40 c +128.16 319.60 128.80 318.96 129.60 318.96 c +130.40 318.96 131.04 319.60 131.04 320.40 c +f +0.60 g +73.44 288.00 m 73.44 288.80 72.80 289.44 72.00 289.44 c +71.20 289.44 70.56 288.80 70.56 288.00 c +70.56 287.20 71.20 286.56 72.00 286.56 c +72.80 286.56 73.44 287.20 73.44 288.00 c +f +0.60 g +91.44 244.80 m 91.44 245.60 90.80 246.24 90.00 246.24 c +89.20 246.24 88.56 245.60 88.56 244.80 c +88.56 244.00 89.20 243.36 90.00 243.36 c +90.80 243.36 91.44 244.00 91.44 244.80 c +f +0.60 g +102.24 234.00 m 102.24 234.80 101.60 235.44 100.80 235.44 c +100.00 235.44 99.36 234.80 99.36 234.00 c +99.36 233.20 100.00 232.56 100.80 232.56 c +101.60 232.56 102.24 233.20 102.24 234.00 c +f +0.60 g +127.44 237.60 m 127.44 238.40 126.80 239.04 126.00 239.04 c +125.20 239.04 124.56 238.40 124.56 237.60 c +124.56 236.80 125.20 236.16 126.00 236.16 c +126.80 236.16 127.44 236.80 127.44 237.60 c +f +0.60 g +159.84 241.20 m 159.84 242.00 159.20 242.64 158.40 242.64 c +157.60 242.64 156.96 242.00 156.96 241.20 c +156.96 240.40 157.60 239.76 158.40 239.76 c +159.20 239.76 159.84 240.40 159.84 241.20 c +f +0.60 g +357.84 288.00 m 357.84 288.80 357.20 289.44 356.40 289.44 c +355.60 289.44 354.96 288.80 354.96 288.00 c +354.96 287.20 355.60 286.56 356.40 286.56 c +357.20 286.56 357.84 287.20 357.84 288.00 c +f +0.60 g +357.84 252.00 m 357.84 252.80 357.20 253.44 356.40 253.44 c +355.60 253.44 354.96 252.80 354.96 252.00 c +354.96 251.20 355.60 250.56 356.40 250.56 c +357.20 250.56 357.84 251.20 357.84 252.00 c +f +0.60 g +296.64 309.60 m 296.64 310.40 296.00 311.04 295.20 311.04 c +294.40 311.04 293.76 310.40 293.76 309.60 c +293.76 308.80 294.40 308.16 295.20 308.16 c +296.00 308.16 296.64 308.80 296.64 309.60 c +f +0.60 g +296.64 234.00 m 296.64 234.80 296.00 235.44 295.20 235.44 c +294.40 235.44 293.76 234.80 293.76 234.00 c +293.76 233.20 294.40 232.56 295.20 232.56 c +296.00 232.56 296.64 233.20 296.64 234.00 c +f +0.60 g +404.64 273.60 m 404.64 274.40 404.00 275.04 403.20 275.04 c +402.40 275.04 401.76 274.40 401.76 273.60 c +401.76 272.80 402.40 272.16 403.20 272.16 c +404.00 272.16 404.64 272.80 404.64 273.60 c +f +0.60 g +404.64 266.40 m 404.64 267.20 404.00 267.84 403.20 267.84 c +402.40 267.84 401.76 267.20 401.76 266.40 c +401.76 265.60 402.40 264.96 403.20 264.96 c +404.00 264.96 404.64 265.60 404.64 266.40 c +f +0.60 g +372.24 316.80 m 372.24 317.60 371.60 318.24 370.80 318.24 c +370.00 318.24 369.36 317.60 369.36 316.80 c +369.36 316.00 370.00 315.36 370.80 315.36 c +371.60 315.36 372.24 316.00 372.24 316.80 c +f +0.60 g +134.64 536.40 m 134.64 537.20 134.00 537.84 133.20 537.84 c +132.40 537.84 131.76 537.20 131.76 536.40 c +131.76 535.60 132.40 534.96 133.20 534.96 c +134.00 534.96 134.64 535.60 134.64 536.40 c +f +0.60 g +134.64 529.20 m 134.64 530.00 134.00 530.64 133.20 530.64 c +132.40 530.64 131.76 530.00 131.76 529.20 c +131.76 528.40 132.40 527.76 133.20 527.76 c +134.00 527.76 134.64 528.40 134.64 529.20 c +f +0.60 g +77.04 536.40 m 77.04 537.20 76.40 537.84 75.60 537.84 c +74.80 537.84 74.16 537.20 74.16 536.40 c +74.16 535.60 74.80 534.96 75.60 534.96 c +76.40 534.96 77.04 535.60 77.04 536.40 c +f +0.60 g +77.04 529.20 m 77.04 530.00 76.40 530.64 75.60 530.64 c +74.80 530.64 74.16 530.00 74.16 529.20 c +74.16 528.40 74.80 527.76 75.60 527.76 c +76.40 527.76 77.04 528.40 77.04 529.20 c +f +0.60 g +530.64 270.00 m 530.64 270.80 530.00 271.44 529.20 271.44 c +528.40 271.44 527.76 270.80 527.76 270.00 c +527.76 269.20 528.40 268.56 529.20 268.56 c +530.00 268.56 530.64 269.20 530.64 270.00 c +f +0.60 g +530.64 277.20 m 530.64 278.00 530.00 278.64 529.20 278.64 c +528.40 278.64 527.76 278.00 527.76 277.20 c +527.76 276.40 528.40 275.76 529.20 275.76 c +530.00 275.76 530.64 276.40 530.64 277.20 c +f +0.60 g +530.64 284.40 m 530.64 285.20 530.00 285.84 529.20 285.84 c +528.40 285.84 527.76 285.20 527.76 284.40 c +527.76 283.60 528.40 282.96 529.20 282.96 c +530.00 282.96 530.64 283.60 530.64 284.40 c +f +0.60 g +530.64 291.60 m 530.64 292.40 530.00 293.04 529.20 293.04 c +528.40 293.04 527.76 292.40 527.76 291.60 c +527.76 290.80 528.40 290.16 529.20 290.16 c +530.00 290.16 530.64 290.80 530.64 291.60 c +f +0.60 g +163.44 147.60 m 163.44 148.40 162.80 149.04 162.00 149.04 c +161.20 149.04 160.56 148.40 160.56 147.60 c +160.56 146.80 161.20 146.16 162.00 146.16 c +162.80 146.16 163.44 146.80 163.44 147.60 c +f +0.60 g +141.84 111.60 m 141.84 112.40 141.20 113.04 140.40 113.04 c +139.60 113.04 138.96 112.40 138.96 111.60 c +138.96 110.80 139.60 110.16 140.40 110.16 c +141.20 110.16 141.84 110.80 141.84 111.60 c +f +0.60 g +300.24 147.60 m 300.24 148.40 299.60 149.04 298.80 149.04 c +298.00 149.04 297.36 148.40 297.36 147.60 c +297.36 146.80 298.00 146.16 298.80 146.16 c +299.60 146.16 300.24 146.80 300.24 147.60 c +f +0.60 g +300.24 133.20 m 300.24 134.00 299.60 134.64 298.80 134.64 c +298.00 134.64 297.36 134.00 297.36 133.20 c +297.36 132.40 298.00 131.76 298.80 131.76 c +299.60 131.76 300.24 132.40 300.24 133.20 c +f +0.60 g +163.44 140.40 m 163.44 141.20 162.80 141.84 162.00 141.84 c +161.20 141.84 160.56 141.20 160.56 140.40 c +160.56 139.60 161.20 138.96 162.00 138.96 c +162.80 138.96 163.44 139.60 163.44 140.40 c +f +0.60 g +95.04 154.80 m 95.04 155.60 94.40 156.24 93.60 156.24 c +92.80 156.24 92.16 155.60 92.16 154.80 c +92.16 154.00 92.80 153.36 93.60 153.36 c +94.40 153.36 95.04 154.00 95.04 154.80 c +f +0.60 g +95.04 147.60 m 95.04 148.40 94.40 149.04 93.60 149.04 c +92.80 149.04 92.16 148.40 92.16 147.60 c +92.16 146.80 92.80 146.16 93.60 146.16 c +94.40 146.16 95.04 146.80 95.04 147.60 c +f +0.60 g +95.04 140.40 m 95.04 141.20 94.40 141.84 93.60 141.84 c +92.80 141.84 92.16 141.20 92.16 140.40 c +92.16 139.60 92.80 138.96 93.60 138.96 c +94.40 138.96 95.04 139.60 95.04 140.40 c +f +0.60 g +95.04 133.20 m 95.04 134.00 94.40 134.64 93.60 134.64 c +92.80 134.64 92.16 134.00 92.16 133.20 c +92.16 132.40 92.80 131.76 93.60 131.76 c +94.40 131.76 95.04 132.40 95.04 133.20 c +f +0.60 g +95.04 126.00 m 95.04 126.80 94.40 127.44 93.60 127.44 c +92.80 127.44 92.16 126.80 92.16 126.00 c +92.16 125.20 92.80 124.56 93.60 124.56 c +94.40 124.56 95.04 125.20 95.04 126.00 c +f +0.60 g +95.04 118.80 m 95.04 119.60 94.40 120.24 93.60 120.24 c +92.80 120.24 92.16 119.60 92.16 118.80 c +92.16 118.00 92.80 117.36 93.60 117.36 c +94.40 117.36 95.04 118.00 95.04 118.80 c +f +0.60 g +95.04 111.60 m 95.04 112.40 94.40 113.04 93.60 113.04 c +92.80 113.04 92.16 112.40 92.16 111.60 c +92.16 110.80 92.80 110.16 93.60 110.16 c +94.40 110.16 95.04 110.80 95.04 111.60 c +f +0.60 g +163.44 133.20 m 163.44 134.00 162.80 134.64 162.00 134.64 c +161.20 134.64 160.56 134.00 160.56 133.20 c +160.56 132.40 161.20 131.76 162.00 131.76 c +162.80 131.76 163.44 132.40 163.44 133.20 c +f +0.60 g +138.24 126.00 m 138.24 126.80 137.60 127.44 136.80 127.44 c +136.00 127.44 135.36 126.80 135.36 126.00 c +135.36 125.20 136.00 124.56 136.80 124.56 c +137.60 124.56 138.24 125.20 138.24 126.00 c +f +0.60 g +145.44 158.40 m 145.44 159.20 144.80 159.84 144.00 159.84 c +143.20 159.84 142.56 159.20 142.56 158.40 c +142.56 157.60 143.20 156.96 144.00 156.96 c +144.80 156.96 145.44 157.60 145.44 158.40 c +f +0.60 g +213.84 61.20 m 213.84 62.00 213.20 62.64 212.40 62.64 c +211.60 62.64 210.96 62.00 210.96 61.20 c +210.96 60.40 211.60 59.76 212.40 59.76 c +213.20 59.76 213.84 60.40 213.84 61.20 c +f +0.60 g +221.04 61.20 m 221.04 62.00 220.40 62.64 219.60 62.64 c +218.80 62.64 218.16 62.00 218.16 61.20 c +218.16 60.40 218.80 59.76 219.60 59.76 c +220.40 59.76 221.04 60.40 221.04 61.20 c +f +0.60 g +1319.04 770.40 m 1319.04 771.20 1318.40 771.84 1317.60 771.84 c +1316.80 771.84 1316.16 771.20 1316.16 770.40 c +1316.16 769.60 1316.80 768.96 1317.60 768.96 c +1318.40 768.96 1319.04 769.60 1319.04 770.40 c +f +0.60 g +1319.04 759.60 m 1319.04 760.40 1318.40 761.04 1317.60 761.04 c +1316.80 761.04 1316.16 760.40 1316.16 759.60 c +1316.16 758.80 1316.80 758.16 1317.60 758.16 c +1318.40 758.16 1319.04 758.80 1319.04 759.60 c +f +0.60 g +1250.64 644.40 m 1250.64 645.20 1250.00 645.84 1249.20 645.84 c +1248.40 645.84 1247.76 645.20 1247.76 644.40 c +1247.76 643.60 1248.40 642.96 1249.20 642.96 c +1250.00 642.96 1250.64 643.60 1250.64 644.40 c +f +0.60 g +1250.64 633.60 m 1250.64 634.40 1250.00 635.04 1249.20 635.04 c +1248.40 635.04 1247.76 634.40 1247.76 633.60 c +1247.76 632.80 1248.40 632.16 1249.20 632.16 c +1250.00 632.16 1250.64 632.80 1250.64 633.60 c +f +0.60 g +1275.84 529.20 m 1275.84 530.00 1275.20 530.64 1274.40 530.64 c +1273.60 530.64 1272.96 530.00 1272.96 529.20 c +1272.96 528.40 1273.60 527.76 1274.40 527.76 c +1275.20 527.76 1275.84 528.40 1275.84 529.20 c +f +0.60 g +1319.04 529.20 m 1319.04 530.00 1318.40 530.64 1317.60 530.64 c +1316.80 530.64 1316.16 530.00 1316.16 529.20 c +1316.16 528.40 1316.80 527.76 1317.60 527.76 c +1318.40 527.76 1319.04 528.40 1319.04 529.20 c +f +0.60 g +1275.84 536.40 m 1275.84 537.20 1275.20 537.84 1274.40 537.84 c +1273.60 537.84 1272.96 537.20 1272.96 536.40 c +1272.96 535.60 1273.60 534.96 1274.40 534.96 c +1275.20 534.96 1275.84 535.60 1275.84 536.40 c +f +0.60 g +1319.04 536.40 m 1319.04 537.20 1318.40 537.84 1317.60 537.84 c +1316.80 537.84 1316.16 537.20 1316.16 536.40 c +1316.16 535.60 1316.80 534.96 1317.60 534.96 c +1318.40 534.96 1319.04 535.60 1319.04 536.40 c +f +0.60 g +1279.44 514.80 m 1279.44 515.60 1278.80 516.24 1278.00 516.24 c +1277.20 516.24 1276.56 515.60 1276.56 514.80 c +1276.56 514.00 1277.20 513.36 1278.00 513.36 c +1278.80 513.36 1279.44 514.00 1279.44 514.80 c +f +0.60 g +1279.44 507.60 m 1279.44 508.40 1278.80 509.04 1278.00 509.04 c +1277.20 509.04 1276.56 508.40 1276.56 507.60 c +1276.56 506.80 1277.20 506.16 1278.00 506.16 c +1278.80 506.16 1279.44 506.80 1279.44 507.60 c +f +0.60 g +51.84 75.60 m 51.84 76.40 51.20 77.04 50.40 77.04 c +49.60 77.04 48.96 76.40 48.96 75.60 c +48.96 74.80 49.60 74.16 50.40 74.16 c +51.20 74.16 51.84 74.80 51.84 75.60 c +f +0.60 g +120.24 75.60 m 120.24 76.40 119.60 77.04 118.80 77.04 c +118.00 77.04 117.36 76.40 117.36 75.60 c +117.36 74.80 118.00 74.16 118.80 74.16 c +119.60 74.16 120.24 74.80 120.24 75.60 c +f +0.60 g +120.24 61.20 m 120.24 62.00 119.60 62.64 118.80 62.64 c +118.00 62.64 117.36 62.00 117.36 61.20 c +117.36 60.40 118.00 59.76 118.80 59.76 c +119.60 59.76 120.24 60.40 120.24 61.20 c +f +0.60 g +120.24 54.00 m 120.24 54.80 119.60 55.44 118.80 55.44 c +118.00 55.44 117.36 54.80 117.36 54.00 c +117.36 53.20 118.00 52.56 118.80 52.56 c +119.60 52.56 120.24 53.20 120.24 54.00 c +f +0.60 g +120.24 46.80 m 120.24 47.60 119.60 48.24 118.80 48.24 c +118.00 48.24 117.36 47.60 117.36 46.80 c +117.36 46.00 118.00 45.36 118.80 45.36 c +119.60 45.36 120.24 46.00 120.24 46.80 c +f +0.60 g +120.24 39.60 m 120.24 40.40 119.60 41.04 118.80 41.04 c +118.00 41.04 117.36 40.40 117.36 39.60 c +117.36 38.80 118.00 38.16 118.80 38.16 c +119.60 38.16 120.24 38.80 120.24 39.60 c +f +0.60 g +51.84 39.60 m 51.84 40.40 51.20 41.04 50.40 41.04 c +49.60 41.04 48.96 40.40 48.96 39.60 c +48.96 38.80 49.60 38.16 50.40 38.16 c +51.20 38.16 51.84 38.80 51.84 39.60 c +f +0.60 g +51.84 46.80 m 51.84 47.60 51.20 48.24 50.40 48.24 c +49.60 48.24 48.96 47.60 48.96 46.80 c +48.96 46.00 49.60 45.36 50.40 45.36 c +51.20 45.36 51.84 46.00 51.84 46.80 c +f +0.60 g +51.84 54.00 m 51.84 54.80 51.20 55.44 50.40 55.44 c +49.60 55.44 48.96 54.80 48.96 54.00 c +48.96 53.20 49.60 52.56 50.40 52.56 c +51.20 52.56 51.84 53.20 51.84 54.00 c +f +0.60 g +51.84 61.20 m 51.84 62.00 51.20 62.64 50.40 62.64 c +49.60 62.64 48.96 62.00 48.96 61.20 c +48.96 60.40 49.60 59.76 50.40 59.76 c +51.20 59.76 51.84 60.40 51.84 61.20 c +f +0.60 g +120.24 68.40 m 120.24 69.20 119.60 69.84 118.80 69.84 c +118.00 69.84 117.36 69.20 117.36 68.40 c +117.36 67.60 118.00 66.96 118.80 66.96 c +119.60 66.96 120.24 67.60 120.24 68.40 c +f +0.60 g +51.84 68.40 m 51.84 69.20 51.20 69.84 50.40 69.84 c +49.60 69.84 48.96 69.20 48.96 68.40 c +48.96 67.60 49.60 66.96 50.40 66.96 c +51.20 66.96 51.84 67.60 51.84 68.40 c +f +0.60 g +1308.24 644.40 m 1308.24 645.20 1307.60 645.84 1306.80 645.84 c +1306.00 645.84 1305.36 645.20 1305.36 644.40 c +1305.36 643.60 1306.00 642.96 1306.80 642.96 c +1307.60 642.96 1308.24 643.60 1308.24 644.40 c +f +0.60 g +1308.24 633.60 m 1308.24 634.40 1307.60 635.04 1306.80 635.04 c +1306.00 635.04 1305.36 634.40 1305.36 633.60 c +1305.36 632.80 1306.00 632.16 1306.80 632.16 c +1307.60 632.16 1308.24 632.80 1308.24 633.60 c +f +0.60 g +912.24 615.60 m 912.24 616.40 911.60 617.04 910.80 617.04 c +910.00 617.04 909.36 616.40 909.36 615.60 c +909.36 614.80 910.00 614.16 910.80 614.16 c +911.60 614.16 912.24 614.80 912.24 615.60 c +f +0.60 g +912.24 608.40 m 912.24 609.20 911.60 609.84 910.80 609.84 c +910.00 609.84 909.36 609.20 909.36 608.40 c +909.36 607.60 910.00 606.96 910.80 606.96 c +911.60 606.96 912.24 607.60 912.24 608.40 c +f +0.60 g +912.24 601.20 m 912.24 602.00 911.60 602.64 910.80 602.64 c +910.00 602.64 909.36 602.00 909.36 601.20 c +909.36 600.40 910.00 599.76 910.80 599.76 c +911.60 599.76 912.24 600.40 912.24 601.20 c +f +0.60 g +912.24 594.00 m 912.24 594.80 911.60 595.44 910.80 595.44 c +910.00 595.44 909.36 594.80 909.36 594.00 c +909.36 593.20 910.00 592.56 910.80 592.56 c +911.60 592.56 912.24 593.20 912.24 594.00 c +f +0.60 g +912.24 586.80 m 912.24 587.60 911.60 588.24 910.80 588.24 c +910.00 588.24 909.36 587.60 909.36 586.80 c +909.36 586.00 910.00 585.36 910.80 585.36 c +911.60 585.36 912.24 586.00 912.24 586.80 c +f +0.60 g +912.24 579.60 m 912.24 580.40 911.60 581.04 910.80 581.04 c +910.00 581.04 909.36 580.40 909.36 579.60 c +909.36 578.80 910.00 578.16 910.80 578.16 c +911.60 578.16 912.24 578.80 912.24 579.60 c +f +0.60 g +1261.44 770.40 m 1261.44 771.20 1260.80 771.84 1260.00 771.84 c +1259.20 771.84 1258.56 771.20 1258.56 770.40 c +1258.56 769.60 1259.20 768.96 1260.00 768.96 c +1260.80 768.96 1261.44 769.60 1261.44 770.40 c +f +0.60 g +1261.44 759.60 m 1261.44 760.40 1260.80 761.04 1260.00 761.04 c +1259.20 761.04 1258.56 760.40 1258.56 759.60 c +1258.56 758.80 1259.20 758.16 1260.00 758.16 c +1260.80 758.16 1261.44 758.80 1261.44 759.60 c +f +0.60 g +1290.24 698.40 m 1290.24 699.20 1289.60 699.84 1288.80 699.84 c +1288.00 699.84 1287.36 699.20 1287.36 698.40 c +1287.36 697.60 1288.00 696.96 1288.80 696.96 c +1289.60 696.96 1290.24 697.60 1290.24 698.40 c +f +0.60 g +1297.44 687.60 m 1297.44 688.40 1296.80 689.04 1296.00 689.04 c +1295.20 689.04 1294.56 688.40 1294.56 687.60 c +1294.56 686.80 1295.20 686.16 1296.00 686.16 c +1296.80 686.16 1297.44 686.80 1297.44 687.60 c +f +0.60 g +1340.64 698.40 m 1340.64 699.20 1340.00 699.84 1339.20 699.84 c +1338.40 699.84 1337.76 699.20 1337.76 698.40 c +1337.76 697.60 1338.40 696.96 1339.20 696.96 c +1340.00 696.96 1340.64 697.60 1340.64 698.40 c +f +0.60 g +1311.84 687.60 m 1311.84 688.40 1311.20 689.04 1310.40 689.04 c +1309.60 689.04 1308.96 688.40 1308.96 687.60 c +1308.96 686.80 1309.60 686.16 1310.40 686.16 c +1311.20 686.16 1311.84 686.80 1311.84 687.60 c +f +0.60 g +1293.84 741.60 m 1293.84 742.40 1293.20 743.04 1292.40 743.04 c +1291.60 743.04 1290.96 742.40 1290.96 741.60 c +1290.96 740.80 1291.60 740.16 1292.40 740.16 c +1293.20 740.16 1293.84 740.80 1293.84 741.60 c +f +0.60 g +1272.24 705.60 m 1272.24 706.40 1271.60 707.04 1270.80 707.04 c +1270.00 707.04 1269.36 706.40 1269.36 705.60 c +1269.36 704.80 1270.00 704.16 1270.80 704.16 c +1271.60 704.16 1272.24 704.80 1272.24 705.60 c +f +0.60 g +1272.24 712.80 m 1272.24 713.60 1271.60 714.24 1270.80 714.24 c +1270.00 714.24 1269.36 713.60 1269.36 712.80 c +1269.36 712.00 1270.00 711.36 1270.80 711.36 c +1271.60 711.36 1272.24 712.00 1272.24 712.80 c +f +0.60 g +1272.24 720.00 m 1272.24 720.80 1271.60 721.44 1270.80 721.44 c +1270.00 721.44 1269.36 720.80 1269.36 720.00 c +1269.36 719.20 1270.00 718.56 1270.80 718.56 c +1271.60 718.56 1272.24 719.20 1272.24 720.00 c +f +0.60 g +1272.24 727.20 m 1272.24 728.00 1271.60 728.64 1270.80 728.64 c +1270.00 728.64 1269.36 728.00 1269.36 727.20 c +1269.36 726.40 1270.00 725.76 1270.80 725.76 c +1271.60 725.76 1272.24 726.40 1272.24 727.20 c +f +0.60 g +1340.64 741.60 m 1340.64 742.40 1340.00 743.04 1339.20 743.04 c +1338.40 743.04 1337.76 742.40 1337.76 741.60 c +1337.76 740.80 1338.40 740.16 1339.20 740.16 c +1340.00 740.16 1340.64 740.80 1340.64 741.60 c +f +0.60 g +1340.64 734.40 m 1340.64 735.20 1340.00 735.84 1339.20 735.84 c +1338.40 735.84 1337.76 735.20 1337.76 734.40 c +1337.76 733.60 1338.40 732.96 1339.20 732.96 c +1340.00 732.96 1340.64 733.60 1340.64 734.40 c +f +0.60 g +1340.64 727.20 m 1340.64 728.00 1340.00 728.64 1339.20 728.64 c +1338.40 728.64 1337.76 728.00 1337.76 727.20 c +1337.76 726.40 1338.40 725.76 1339.20 725.76 c +1340.00 725.76 1340.64 726.40 1340.64 727.20 c +f +0.60 g +1340.64 720.00 m 1340.64 720.80 1340.00 721.44 1339.20 721.44 c +1338.40 721.44 1337.76 720.80 1337.76 720.00 c +1337.76 719.20 1338.40 718.56 1339.20 718.56 c +1340.00 718.56 1340.64 719.20 1340.64 720.00 c +f +0.60 g +1340.64 712.80 m 1340.64 713.60 1340.00 714.24 1339.20 714.24 c +1338.40 714.24 1337.76 713.60 1337.76 712.80 c +1337.76 712.00 1338.40 711.36 1339.20 711.36 c +1340.00 711.36 1340.64 712.00 1340.64 712.80 c +f +0.60 g +1340.64 705.60 m 1340.64 706.40 1340.00 707.04 1339.20 707.04 c +1338.40 707.04 1337.76 706.40 1337.76 705.60 c +1337.76 704.80 1338.40 704.16 1339.20 704.16 c +1340.00 704.16 1340.64 704.80 1340.64 705.60 c +f +0.60 g +901.44 320.40 m 901.44 321.20 900.80 321.84 900.00 321.84 c +899.20 321.84 898.56 321.20 898.56 320.40 c +898.56 319.60 899.20 318.96 900.00 318.96 c +900.80 318.96 901.44 319.60 901.44 320.40 c +f +0.60 g +901.44 284.40 m 901.44 285.20 900.80 285.84 900.00 285.84 c +899.20 285.84 898.56 285.20 898.56 284.40 c +898.56 283.60 899.20 282.96 900.00 282.96 c +900.80 282.96 901.44 283.60 901.44 284.40 c +f +0.60 g +901.44 266.40 m 901.44 267.20 900.80 267.84 900.00 267.84 c +899.20 267.84 898.56 267.20 898.56 266.40 c +898.56 265.60 899.20 264.96 900.00 264.96 c +900.80 264.96 901.44 265.60 901.44 266.40 c +f +0.60 g +901.44 230.40 m 901.44 231.20 900.80 231.84 900.00 231.84 c +899.20 231.84 898.56 231.20 898.56 230.40 c +898.56 229.60 899.20 228.96 900.00 228.96 c +900.80 228.96 901.44 229.60 901.44 230.40 c +f +0.60 g +962.64 266.40 m 962.64 267.20 962.00 267.84 961.20 267.84 c +960.40 267.84 959.76 267.20 959.76 266.40 c +959.76 265.60 960.40 264.96 961.20 264.96 c +962.00 264.96 962.64 265.60 962.64 266.40 c +f +0.60 g +962.64 230.40 m 962.64 231.20 962.00 231.84 961.20 231.84 c +960.40 231.84 959.76 231.20 959.76 230.40 c +959.76 229.60 960.40 228.96 961.20 228.96 c +962.00 228.96 962.64 229.60 962.64 230.40 c +f +0.60 g +962.64 320.40 m 962.64 321.20 962.00 321.84 961.20 321.84 c +960.40 321.84 959.76 321.20 959.76 320.40 c +959.76 319.60 960.40 318.96 961.20 318.96 c +962.00 318.96 962.64 319.60 962.64 320.40 c +f +0.60 g +962.64 284.40 m 962.64 285.20 962.00 285.84 961.20 285.84 c +960.40 285.84 959.76 285.20 959.76 284.40 c +959.76 283.60 960.40 282.96 961.20 282.96 c +962.00 282.96 962.64 283.60 962.64 284.40 c +f +0.60 g +1023.84 266.40 m 1023.84 267.20 1023.20 267.84 1022.40 267.84 c +1021.60 267.84 1020.96 267.20 1020.96 266.40 c +1020.96 265.60 1021.60 264.96 1022.40 264.96 c +1023.20 264.96 1023.84 265.60 1023.84 266.40 c +f +0.60 g +1023.84 230.40 m 1023.84 231.20 1023.20 231.84 1022.40 231.84 c +1021.60 231.84 1020.96 231.20 1020.96 230.40 c +1020.96 229.60 1021.60 228.96 1022.40 228.96 c +1023.20 228.96 1023.84 229.60 1023.84 230.40 c +f +0.60 g +1023.84 320.40 m 1023.84 321.20 1023.20 321.84 1022.40 321.84 c +1021.60 321.84 1020.96 321.20 1020.96 320.40 c +1020.96 319.60 1021.60 318.96 1022.40 318.96 c +1023.20 318.96 1023.84 319.60 1023.84 320.40 c +f +0.60 g +1023.84 284.40 m 1023.84 285.20 1023.20 285.84 1022.40 285.84 c +1021.60 285.84 1020.96 285.20 1020.96 284.40 c +1020.96 283.60 1021.60 282.96 1022.40 282.96 c +1023.20 282.96 1023.84 283.60 1023.84 284.40 c +f +0.60 g +908.64 324.00 m 908.64 324.80 908.00 325.44 907.20 325.44 c +906.40 325.44 905.76 324.80 905.76 324.00 c +905.76 323.20 906.40 322.56 907.20 322.56 c +908.00 322.56 908.64 323.20 908.64 324.00 c +f +0.60 g +908.64 284.40 m 908.64 285.20 908.00 285.84 907.20 285.84 c +906.40 285.84 905.76 285.20 905.76 284.40 c +905.76 283.60 906.40 282.96 907.20 282.96 c +908.00 282.96 908.64 283.60 908.64 284.40 c +f +0.60 g +969.84 324.00 m 969.84 324.80 969.20 325.44 968.40 325.44 c +967.60 325.44 966.96 324.80 966.96 324.00 c +966.96 323.20 967.60 322.56 968.40 322.56 c +969.20 322.56 969.84 323.20 969.84 324.00 c +f +0.60 g +1031.04 324.00 m 1031.04 324.80 1030.40 325.44 1029.60 325.44 c +1028.80 325.44 1028.16 324.80 1028.16 324.00 c +1028.16 323.20 1028.80 322.56 1029.60 322.56 c +1030.40 322.56 1031.04 323.20 1031.04 324.00 c +f +0.60 g +1031.04 284.40 m 1031.04 285.20 1030.40 285.84 1029.60 285.84 c +1028.80 285.84 1028.16 285.20 1028.16 284.40 c +1028.16 283.60 1028.80 282.96 1029.60 282.96 c +1030.40 282.96 1031.04 283.60 1031.04 284.40 c +f +0.60 g +969.84 284.40 m 969.84 285.20 969.20 285.84 968.40 285.84 c +967.60 285.84 966.96 285.20 966.96 284.40 c +966.96 283.60 967.60 282.96 968.40 282.96 c +969.20 282.96 969.84 283.60 969.84 284.40 c +f +0.60 g +908.64 266.40 m 908.64 267.20 908.00 267.84 907.20 267.84 c +906.40 267.84 905.76 267.20 905.76 266.40 c +905.76 265.60 906.40 264.96 907.20 264.96 c +908.00 264.96 908.64 265.60 908.64 266.40 c +f +0.60 g +908.64 230.40 m 908.64 231.20 908.00 231.84 907.20 231.84 c +906.40 231.84 905.76 231.20 905.76 230.40 c +905.76 229.60 906.40 228.96 907.20 228.96 c +908.00 228.96 908.64 229.60 908.64 230.40 c +f +0.60 g +969.84 266.40 m 969.84 267.20 969.20 267.84 968.40 267.84 c +967.60 267.84 966.96 267.20 966.96 266.40 c +966.96 265.60 967.60 264.96 968.40 264.96 c +969.20 264.96 969.84 265.60 969.84 266.40 c +f +0.60 g +1031.04 266.40 m 1031.04 267.20 1030.40 267.84 1029.60 267.84 c +1028.80 267.84 1028.16 267.20 1028.16 266.40 c +1028.16 265.60 1028.80 264.96 1029.60 264.96 c +1030.40 264.96 1031.04 265.60 1031.04 266.40 c +f +0.60 g +1031.04 230.40 m 1031.04 231.20 1030.40 231.84 1029.60 231.84 c +1028.80 231.84 1028.16 231.20 1028.16 230.40 c +1028.16 229.60 1028.80 228.96 1029.60 228.96 c +1030.40 228.96 1031.04 229.60 1031.04 230.40 c +f +0.60 g +969.84 230.40 m 969.84 231.20 969.20 231.84 968.40 231.84 c +967.60 231.84 966.96 231.20 966.96 230.40 c +966.96 229.60 967.60 228.96 968.40 228.96 c +969.20 228.96 969.84 229.60 969.84 230.40 c +f +0.60 g +397.44 144.00 m 397.44 144.80 396.80 145.44 396.00 145.44 c +395.20 145.44 394.56 144.80 394.56 144.00 c +394.56 143.20 395.20 142.56 396.00 142.56 c +396.80 142.56 397.44 143.20 397.44 144.00 c +f +0.60 g +397.44 104.40 m 397.44 105.20 396.80 105.84 396.00 105.84 c +395.20 105.84 394.56 105.20 394.56 104.40 c +394.56 103.60 395.20 102.96 396.00 102.96 c +396.80 102.96 397.44 103.60 397.44 104.40 c +f +0.60 g +397.44 64.80 m 397.44 65.60 396.80 66.24 396.00 66.24 c +395.20 66.24 394.56 65.60 394.56 64.80 c +394.56 64.00 395.20 63.36 396.00 63.36 c +396.80 63.36 397.44 64.00 397.44 64.80 c +f +0.60 g +944.64 208.80 m 944.64 209.60 944.00 210.24 943.20 210.24 c +942.40 210.24 941.76 209.60 941.76 208.80 c +941.76 208.00 942.40 207.36 943.20 207.36 c +944.00 207.36 944.64 208.00 944.64 208.80 c +f +0.60 g +897.84 208.80 m 897.84 209.60 897.20 210.24 896.40 210.24 c +895.60 210.24 894.96 209.60 894.96 208.80 c +894.96 208.00 895.60 207.36 896.40 207.36 c +897.20 207.36 897.84 208.00 897.84 208.80 c +f +0.60 g +595.44 147.60 m 595.44 148.40 594.80 149.04 594.00 149.04 c +593.20 149.04 592.56 148.40 592.56 147.60 c +592.56 146.80 593.20 146.16 594.00 146.16 c +594.80 146.16 595.44 146.80 595.44 147.60 c +f +0.60 g +768.24 284.40 m 768.24 285.20 767.60 285.84 766.80 285.84 c +766.00 285.84 765.36 285.20 765.36 284.40 c +765.36 283.60 766.00 282.96 766.80 282.96 c +767.60 282.96 768.24 283.60 768.24 284.40 c +f +0.60 g +768.24 277.20 m 768.24 278.00 767.60 278.64 766.80 278.64 c +766.00 278.64 765.36 278.00 765.36 277.20 c +765.36 276.40 766.00 275.76 766.80 275.76 c +767.60 275.76 768.24 276.40 768.24 277.20 c +f +0.60 g +768.24 270.00 m 768.24 270.80 767.60 271.44 766.80 271.44 c +766.00 271.44 765.36 270.80 765.36 270.00 c +765.36 269.20 766.00 268.56 766.80 268.56 c +767.60 268.56 768.24 269.20 768.24 270.00 c +f +0.60 g +768.24 262.80 m 768.24 263.60 767.60 264.24 766.80 264.24 c +766.00 264.24 765.36 263.60 765.36 262.80 c +765.36 262.00 766.00 261.36 766.80 261.36 c +767.60 261.36 768.24 262.00 768.24 262.80 c +f +0.60 g +768.24 255.60 m 768.24 256.40 767.60 257.04 766.80 257.04 c +766.00 257.04 765.36 256.40 765.36 255.60 c +765.36 254.80 766.00 254.16 766.80 254.16 c +767.60 254.16 768.24 254.80 768.24 255.60 c +f +0.60 g +768.24 241.20 m 768.24 242.00 767.60 242.64 766.80 242.64 c +766.00 242.64 765.36 242.00 765.36 241.20 c +765.36 240.40 766.00 239.76 766.80 239.76 c +767.60 239.76 768.24 240.40 768.24 241.20 c +f +0.60 g +768.24 234.00 m 768.24 234.80 767.60 235.44 766.80 235.44 c +766.00 235.44 765.36 234.80 765.36 234.00 c +765.36 233.20 766.00 232.56 766.80 232.56 c +767.60 232.56 768.24 233.20 768.24 234.00 c +f +0.60 g +768.24 226.80 m 768.24 227.60 767.60 228.24 766.80 228.24 c +766.00 228.24 765.36 227.60 765.36 226.80 c +765.36 226.00 766.00 225.36 766.80 225.36 c +767.60 225.36 768.24 226.00 768.24 226.80 c +f +0.60 g +786.24 219.60 m 786.24 220.40 785.60 221.04 784.80 221.04 c +784.00 221.04 783.36 220.40 783.36 219.60 c +783.36 218.80 784.00 218.16 784.80 218.16 c +785.60 218.16 786.24 218.80 786.24 219.60 c +f +0.60 g +786.24 212.40 m 786.24 213.20 785.60 213.84 784.80 213.84 c +784.00 213.84 783.36 213.20 783.36 212.40 c +783.36 211.60 784.00 210.96 784.80 210.96 c +785.60 210.96 786.24 211.60 786.24 212.40 c +f +0.60 g +786.24 190.80 m 786.24 191.60 785.60 192.24 784.80 192.24 c +784.00 192.24 783.36 191.60 783.36 190.80 c +783.36 190.00 784.00 189.36 784.80 189.36 c +785.60 189.36 786.24 190.00 786.24 190.80 c +f +0.60 g +768.24 176.40 m 768.24 177.20 767.60 177.84 766.80 177.84 c +766.00 177.84 765.36 177.20 765.36 176.40 c +765.36 175.60 766.00 174.96 766.80 174.96 c +767.60 174.96 768.24 175.60 768.24 176.40 c +f +0.60 g +786.24 169.20 m 786.24 170.00 785.60 170.64 784.80 170.64 c +784.00 170.64 783.36 170.00 783.36 169.20 c +783.36 168.40 784.00 167.76 784.80 167.76 c +785.60 167.76 786.24 168.40 786.24 169.20 c +f +0.60 g +786.24 162.00 m 786.24 162.80 785.60 163.44 784.80 163.44 c +784.00 163.44 783.36 162.80 783.36 162.00 c +783.36 161.20 784.00 160.56 784.80 160.56 c +785.60 160.56 786.24 161.20 786.24 162.00 c +f +0.60 g +782.64 147.60 m 782.64 148.40 782.00 149.04 781.20 149.04 c +780.40 149.04 779.76 148.40 779.76 147.60 c +779.76 146.80 780.40 146.16 781.20 146.16 c +782.00 146.16 782.64 146.80 782.64 147.60 c +f +0.60 g +653.04 172.80 m 653.04 173.60 652.40 174.24 651.60 174.24 c +650.80 174.24 650.16 173.60 650.16 172.80 c +650.16 172.00 650.80 171.36 651.60 171.36 c +652.40 171.36 653.04 172.00 653.04 172.80 c +f +0.60 g +642.24 223.20 m 642.24 224.00 641.60 224.64 640.80 224.64 c +640.00 224.64 639.36 224.00 639.36 223.20 c +639.36 222.40 640.00 221.76 640.80 221.76 c +641.60 221.76 642.24 222.40 642.24 223.20 c +f +0.60 g +642.24 201.60 m 642.24 202.40 641.60 203.04 640.80 203.04 c +640.00 203.04 639.36 202.40 639.36 201.60 c +639.36 200.80 640.00 200.16 640.80 200.16 c +641.60 200.16 642.24 200.80 642.24 201.60 c +f +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +14.40 802.43 1369.13 -788.03 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +21.60 795.23 1354.73 -773.63 re +S +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +126.69 15.12 Td +<0031> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +126.69 795.95 Td +<0031> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +354.88 15.12 Td +<0032> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +354.88 795.95 Td +<0032> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +583.07 15.12 Td +<0033> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +583.07 795.95 Td +<0033> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +811.26 15.12 Td +<0034> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +811.26 795.95 Td +<0034> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1039.45 15.12 Td +<0035> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1039.45 795.95 Td +<0035> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1267.64 15.12 Td +<0036> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1267.64 795.95 Td +<0036> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +16.20 701.05 Td +<0041> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1378.13 701.05 Td +<0041> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +16.20 504.04 Td +<0042> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1378.13 504.04 Td +<0042> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +16.20 307.03 Td +<0043> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1378.13 307.03 Td +<0043> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +16.20 110.02 Td +<0044> Tj +ET +7.20 w +BT +/F1 7.199999999999999 Tf +7.20 TL +0.627 0.000 0.000 rg +1378.13 110.02 Td +<0044> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +242.589 14.400 m +242.589 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +242.589 802.431 m +242.589 795.231 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +470.778 14.400 m +470.778 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +470.778 802.431 m +470.778 795.231 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.967 14.400 m +698.967 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.967 802.431 m +698.967 795.231 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +927.156 14.400 m +927.156 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +927.156 802.431 m +927.156 795.231 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1155.345 14.400 m +1155.345 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1155.345 802.431 m +1155.345 795.231 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +14.400 605.424 m +21.600 605.424 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1383.534 605.424 m +1376.334 605.424 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +14.400 408.416 m +21.600 408.416 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1383.534 408.416 m +1376.334 408.416 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +14.400 211.408 m +21.600 211.408 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1383.534 211.408 m +1376.334 211.408 l +S +q +1 0 0 1 0 0 cm +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 151.200 m +947.752 151.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 151.200 m +947.752 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 122.400 m +871.614 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 122.400 m +871.614 151.200 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +875.21 132.05 Td +(Schematic) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 151.200 m +1210.063 151.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 151.200 m +1210.063 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 122.400 m +947.752 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 122.400 m +947.752 151.200 l +S +0.00 G +BT +/F2 13.090909090909088 Tf +13.09 TL +0.000 g +1026.51 131.07 Td +(CogletESPV1.1_3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 151.200 m +1267.896 151.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 151.200 m +1267.896 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 136.800 m +1210.063 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 136.800 m +1210.063 151.200 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1213.66 139.25 Td +(Create at) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 151.200 m +1376.334 151.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 151.200 m +1376.334 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 136.800 m +1267.896 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 136.800 m +1267.896 151.200 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1271.50 139.25 Td +(2025-12-19) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 136.800 m +1267.896 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 136.800 m +1267.896 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 122.400 m +1210.063 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 122.400 m +1210.063 136.800 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1213.66 124.85 Td +(Update at) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 136.800 m +1376.334 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 136.800 m +1376.334 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 122.400 m +1267.896 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 122.400 m +1267.896 136.800 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1271.50 124.85 Td +(2026-01-08) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 122.400 m +947.752 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 122.400 m +947.752 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 108.000 m +871.614 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 108.000 m +871.614 122.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +875.21 110.45 Td +(Board) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 122.400 m +1210.063 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 122.400 m +1210.063 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 108.000 m +947.752 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 108.000 m +947.752 122.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1039.70 110.45 Td +(CogletESPV1.1_3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 122.400 m +1267.896 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 122.400 m +1267.896 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 108.000 m +1210.063 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1210.063 108.000 m +1210.063 122.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1213.66 110.45 Td +(Page) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 122.400 m +1376.334 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 122.400 m +1376.334 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 108.000 m +1267.896 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1267.896 108.000 m +1267.896 122.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1271.50 110.45 Td +(P1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 108.000 m +947.752 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 108.000 m +947.752 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 93.600 m +871.614 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 93.600 m +871.614 108.000 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +875.21 96.05 Td +(Drawn) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 108.000 m +1028.762 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 108.000 m +1028.762 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 93.600 m +947.752 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 93.600 m +947.752 108.000 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 108.000 m +1376.334 108.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 108.000 m +1376.334 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 64.800 m +1028.762 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 64.800 m +1028.762 108.000 l +S +0.00 G +BT +/F2 13.090909090909088 Tf +13.09 TL +0.000 g +1170.89 80.67 Td +(CogletESP) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 93.600 m +947.752 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 93.600 m +947.752 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 79.200 m +871.614 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 79.200 m +871.614 93.600 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +875.21 81.65 Td +(Reviewed) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 93.600 m +1028.762 93.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 93.600 m +1028.762 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 79.200 m +947.752 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 79.200 m +947.752 93.600 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 79.200 m +947.752 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 79.200 m +947.752 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 64.800 m +871.614 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 64.800 m +871.614 79.200 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 79.200 m +1028.762 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 79.200 m +1028.762 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 64.800 m +947.752 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 64.800 m +947.752 79.200 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 64.800 m +947.752 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 64.800 m +947.752 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 50.400 m +871.614 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 50.400 m +871.614 64.800 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 64.800 m +1028.762 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 64.800 m +1028.762 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 50.400 m +947.752 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.752 50.400 m +947.752 64.800 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 64.800 m +1095.466 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 64.800 m +1095.466 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 50.400 m +1028.762 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 50.400 m +1028.762 64.800 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1045.83 52.85 Td +(Version) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 64.800 m +1148.962 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 64.800 m +1148.962 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 50.400 m +1095.466 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 50.400 m +1095.466 64.800 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1113.03 52.85 Td +(Size) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 64.800 m +1376.334 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 64.800 m +1376.334 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 50.400 m +1148.962 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 50.400 m +1148.962 64.800 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1226.98 52.85 Td +(Page 1 Total 1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 50.400 m +1028.762 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 50.400 m +1028.762 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 21.600 m +871.614 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +871.614 21.600 m +871.614 50.400 l +S +0.00 G +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 50.400 m +1095.466 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 50.400 m +1095.466 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 21.600 m +1028.762 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1028.762 21.600 m +1028.762 50.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1052.38 31.25 Td +(V1.0) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 50.400 m +1148.962 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 50.400 m +1148.962 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 21.600 m +1095.466 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1095.466 21.600 m +1095.466 50.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1116.57 31.25 Td +(A4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 50.400 m +1376.334 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 50.400 m +1376.334 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1376.334 21.600 m +1148.962 21.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.962 21.600 m +1148.962 50.400 l +S +0.00 G +BT +/F2 9.818181818181817 Tf +9.82 TL +0.000 g +1231.36 31.25 Td +(EasyEDA.com) Tj +ET +q +0.33 0.53 1.00 rg +[] 0 d +951.936 35.170 m +952.088 35.284 952.272 35.341 952.483 35.341 c +952.767 35.341 953.070 35.240 953.393 35.044 c +953.716 34.848 954.026 34.538 954.322 34.114 c +955.470 35.879 l +955.114 36.372 954.672 36.758 954.138 37.030 c +953.604 37.302 953.037 37.435 952.444 37.435 c +951.600 37.435 950.862 37.188 950.242 36.695 c +949.622 36.201 949.312 35.556 949.312 34.772 c +949.312 34.209 949.510 33.671 949.906 33.165 c +950.189 32.805 950.703 32.368 951.442 31.862 c +952.081 31.426 952.477 31.122 952.622 30.952 c +952.767 30.781 952.839 30.616 952.839 30.452 c +952.839 30.249 952.747 30.079 952.556 29.927 c +952.365 29.781 952.114 29.706 951.798 29.706 c +951.000 29.706 950.262 30.129 949.589 30.983 c +948.106 29.326 l +948.765 28.656 949.365 28.188 949.899 27.935 c +950.433 27.682 951.033 27.555 951.686 27.555 c +952.819 27.555 953.683 27.865 954.283 28.485 c +954.883 29.105 955.179 29.769 955.179 30.465 c +955.179 30.996 955.034 31.483 954.744 31.938 c +954.454 32.387 953.848 32.931 952.925 33.564 c +952.345 33.962 952.002 34.228 951.890 34.367 c +951.771 34.506 951.712 34.645 951.712 34.785 c +951.705 34.930 951.784 35.057 951.936 35.170 c +951.936 35.170 l +f +0.33 0.53 1.00 rg +[] 0 d +960.967 31.622 m +959.062 37.194 l +956.702 37.194 l +959.458 29.079 l +956.676 24.361 l +959.214 24.361 l +966.907 37.194 l +964.316 37.194 l +960.967 31.622 l +f +0.33 0.53 1.00 rg +[] 0 d +935.442 35.613 m +930.801 35.613 l +931.184 38.251 l +931.184 38.251 936.108 38.257 936.134 38.257 c +936.781 38.257 937.308 38.763 937.308 39.383 c +937.308 40.003 936.781 40.509 936.134 40.509 c +936.115 40.509 928.988 40.509 928.988 40.509 c +927.169 27.795 l +934.631 27.795 l +934.631 27.795 l +935.258 27.808 935.765 28.301 935.765 28.902 c +935.765 29.516 935.245 30.015 934.605 30.015 c +934.579 30.015 929.977 30.009 929.977 30.009 c +930.465 33.380 l +930.465 33.380 935.192 33.374 935.231 33.374 c +935.877 33.374 936.405 33.880 936.405 34.500 c +936.418 35.063 935.996 35.525 935.442 35.613 c +935.442 35.613 l +f +0.33 0.53 1.00 rg +[] 0 d +976.110 40.502 m +976.090 40.502 968.964 40.502 968.964 40.502 c +967.158 27.802 l +974.627 27.802 l +974.627 27.802 l +975.253 27.814 975.760 28.308 975.760 28.909 c +975.760 29.522 975.240 30.022 974.600 30.022 c +974.574 30.022 969.972 30.015 969.972 30.015 c +970.460 33.387 l +970.460 33.387 975.187 33.380 975.233 33.380 c +975.879 33.380 976.406 33.886 976.406 34.506 c +976.406 35.063 975.985 35.525 975.431 35.613 c +970.790 35.613 l +971.172 38.251 l +971.172 38.251 976.097 38.257 976.123 38.257 c +976.769 38.257 977.296 38.763 977.296 39.383 c +977.283 39.996 976.762 40.502 976.110 40.502 c +976.110 40.502 l +f +0.33 0.53 1.00 rg +[] 0 d +989.446 34.418 m +989.446 35.664 989.143 36.771 988.543 37.726 c +987.943 38.681 987.165 39.383 986.203 39.826 c +985.240 40.275 983.783 40.496 981.812 40.496 c +979.716 40.496 l +977.909 27.795 l +982.023 27.795 l +983.750 27.795 985.102 28.042 986.071 28.535 c +987.040 29.029 987.851 29.813 988.490 30.882 c +989.129 31.957 989.446 33.134 989.446 34.418 c +989.446 34.418 l +986.189 31.793 m +985.708 31.097 985.075 30.604 984.284 30.319 c +983.717 30.117 982.808 30.015 981.548 30.015 c +980.731 30.015 l +981.898 38.263 l +982.524 38.263 l +983.546 38.263 984.363 38.112 984.976 37.802 c +985.589 37.492 986.064 37.055 986.407 36.486 c +986.743 35.917 986.914 35.215 986.914 34.373 c +986.908 33.355 986.671 32.489 986.189 31.793 c +986.189 31.793 l +f +0.33 0.53 1.00 rg +[] 0 d +999.235 34.563 m +997.765 33.785 l +997.647 32.761 996.737 31.970 995.643 31.970 c +994.463 31.970 993.507 32.887 993.507 34.019 c +993.507 35.151 994.463 36.069 995.643 36.069 c +996.097 36.069 996.519 35.929 996.862 35.702 c +998.688 36.669 l +997.699 40.477 l +995.610 40.477 l +988.490 27.827 l +991.153 27.827 l +992.656 30.521 l +997.891 30.521 l +998.589 27.827 l +1000.989 27.827 l +999.235 34.563 l +999.235 34.563 l +f +0.33 0.53 1.00 rg +[] 0 d +994.858 34.070 m +994.858 33.633 995.227 33.279 995.682 33.279 c +996.137 33.279 996.506 33.633 996.506 34.070 c +996.506 34.506 996.137 34.860 995.682 34.860 c +995.227 34.860 994.858 34.506 994.858 34.070 c +994.858 34.070 l +f +0.33 0.53 1.00 rg +[] 0 d +946.207 35.714 m +946.207 35.714 946.207 35.721 946.207 35.714 c +945.383 35.714 l +945.298 35.866 l +944.961 36.378 944.540 36.764 944.032 37.030 c +943.518 37.296 942.707 37.428 942.100 37.428 c +941.197 37.428 940.334 37.194 939.510 36.726 c +938.686 36.258 938.026 35.607 937.539 34.766 c +937.051 33.931 936.800 33.045 936.800 32.122 c +936.800 30.907 937.183 29.845 937.947 28.928 c +938.712 28.010 939.747 27.555 941.046 27.555 c +941.613 27.555 942.120 27.644 942.575 27.833 c +943.030 28.017 943.518 28.339 944.039 28.807 c +944.039 28.807 944.652 28.295 944.658 28.301 c +945.041 28.010 945.515 27.827 946.029 27.795 c +946.267 27.795 l +946.300 28.067 l +947.137 34.829 l +947.130 34.829 947.130 34.829 947.124 34.829 c +947.124 35.316 946.715 35.708 946.207 35.714 c +946.207 35.714 l +944.282 31.179 m +943.986 30.642 943.617 30.243 943.175 29.990 c +942.733 29.737 942.219 29.611 941.626 29.611 c +940.914 29.611 940.334 29.832 939.879 30.287 c +939.424 30.737 939.200 31.331 939.200 32.065 c +939.200 33.020 939.497 33.798 940.096 34.405 c +940.696 35.012 941.421 35.310 942.278 35.310 c +943.017 35.310 943.610 35.082 944.058 34.633 c +944.507 34.177 944.731 33.583 944.731 32.836 c +944.731 32.273 944.579 31.717 944.282 31.179 c +944.282 31.179 l +f +0.33 0.53 1.00 rg +[] 0 d +919.146 39.269 m +918.652 40.528 917.848 41.660 916.786 42.577 c +915.158 43.981 913.048 44.759 910.853 44.759 c +908.955 44.759 907.142 44.190 905.612 43.115 c +904.874 42.596 904.235 41.982 903.707 41.287 c +903.378 41.331 903.041 41.356 902.699 41.356 c +900.807 41.356 899.020 40.648 897.682 39.364 c +896.344 38.080 895.605 36.372 895.605 34.551 c +895.605 32.862 896.258 31.243 897.438 29.990 c +898.374 28.997 899.587 28.295 900.925 27.966 c +901.505 26.309 903.140 25.114 905.059 25.114 c +907.465 25.114 909.423 26.992 909.423 29.301 c +909.423 29.434 909.416 29.573 909.403 29.706 c +915.527 32.792 l +914.189 35.019 l +908.335 32.071 l +907.537 32.944 906.364 33.494 905.059 33.494 c +903.167 33.494 901.552 32.330 900.945 30.711 c +899.403 31.363 898.321 32.836 898.321 34.557 c +898.321 36.872 900.279 38.757 902.699 38.757 c +903.549 38.757 904.347 38.523 905.019 38.118 c +905.830 40.464 908.137 42.160 910.853 42.160 c +914.018 42.160 916.615 39.870 916.964 36.929 c +917.076 36.941 917.188 36.948 917.300 36.948 c +919.192 36.948 920.728 35.474 920.728 33.659 c +920.728 31.938 919.351 30.528 917.597 30.382 c +915.639 30.382 l +915.554 30.401 915.461 30.408 915.369 30.408 c +914.611 30.408 913.998 29.819 913.998 29.092 c +913.998 28.403 914.551 27.840 915.257 27.783 c +915.257 27.770 l +917.597 27.770 l +917.716 27.770 l +917.834 27.783 l +919.364 27.909 920.781 28.573 921.823 29.661 c +922.871 30.755 923.451 32.172 923.451 33.659 c +923.451 36.277 921.638 38.516 919.146 39.269 c +919.146 39.269 l +905.059 30.920 m +905.988 30.920 906.746 30.193 906.746 29.301 c +906.746 28.409 905.988 27.682 905.059 27.682 c +904.129 27.682 903.371 28.409 903.371 29.301 c +903.371 30.193 904.129 30.920 905.059 30.920 c +905.059 30.920 l +f +Q +Q +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.60 748.80 108.00 -198.00 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +188.28 687.60 m 188.28 688.20 187.80 688.68 187.20 688.68 c +186.60 688.68 186.12 688.20 186.12 687.60 c +186.12 687.00 186.60 686.52 187.20 686.52 c +187.80 686.52 188.28 687.00 188.28 687.60 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 673.85 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 677.45 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 676.800 m +183.600 676.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 666.65 Td +(3V3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 670.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 669.600 m +183.600 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 659.45 Td +(EN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 663.05 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 662.400 m +183.600 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 652.25 Td +(IO4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 655.85 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 655.200 m +183.600 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 645.05 Td +(IO5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 648.65 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 648.000 m +183.600 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 637.85 Td +(IO6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 641.45 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 640.800 m +183.600 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 630.65 Td +(IO7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 634.25 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 633.600 m +183.600 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 623.45 Td +(IO15) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 627.05 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 626.400 m +183.600 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 616.25 Td +(IO16) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +179.60 619.85 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 619.200 m +183.600 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 609.05 Td +(IO17) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +175.96 612.65 Td +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 612.000 m +183.600 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 601.85 Td +(IO18) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +175.96 605.45 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 604.800 m +183.600 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 594.65 Td +(IO8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +175.96 598.25 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 597.600 m +183.600 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 587.45 Td +(IO19) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +175.96 591.05 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 590.400 m +183.600 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.26 580.25 Td +(IO20) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +175.96 583.85 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +176.400 583.200 m +183.600 583.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 203.17 552.09 Tm +(IO3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 199.57 541.78 Tm +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +201.600 543.600 m +201.600 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 210.37 552.09 Tm +(IO46) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 206.77 541.78 Tm +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +208.800 543.600 m +208.800 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 217.57 552.09 Tm +(IO9) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 213.97 541.78 Tm +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +216.000 543.600 m +216.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 224.77 552.09 Tm +(IO10) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 221.17 541.78 Tm +(18) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +223.200 543.600 m +223.200 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 231.97 552.09 Tm +(IO11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 228.37 541.78 Tm +(19) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +230.400 543.600 m +230.400 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 239.17 552.09 Tm +(IO12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 235.57 541.78 Tm +(20) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +237.600 543.600 m +237.600 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 246.37 552.09 Tm +(IO13) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 242.77 541.78 Tm +(21) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +244.800 543.600 m +244.800 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 253.57 552.09 Tm +(IO14) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 249.97 541.78 Tm +(22) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +252.000 543.600 m +252.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 260.77 552.09 Tm +(IO21) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 257.17 541.78 Tm +(23) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +259.200 543.600 m +259.200 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 267.97 552.09 Tm +(IO47) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 264.37 541.78 Tm +(24) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +266.400 543.600 m +266.400 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 275.17 552.09 Tm +(IO48) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 271.57 541.78 Tm +(25) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +273.600 543.600 m +273.600 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 282.37 552.09 Tm +(IO45) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 278.77 541.78 Tm +(26) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +280.800 543.600 m +280.800 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +278.38 580.25 Td +(IO0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 583.85 Td +(27) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 583.200 m +291.600 583.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 587.45 Td +(IO35) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 591.05 Td +(28) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 590.400 m +291.600 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 594.65 Td +(IO36) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 598.25 Td +(29) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 597.600 m +291.600 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 601.85 Td +(IO37) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 605.45 Td +(30) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 604.800 m +291.600 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 609.05 Td +(IO38) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 612.65 Td +(31) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 612.000 m +291.600 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 616.25 Td +(IO39) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 619.85 Td +(32) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 619.200 m +291.600 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 623.45 Td +(IO40) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 627.05 Td +(33) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 626.400 m +291.600 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 630.65 Td +(IO41) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 634.25 Td +(34) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 633.600 m +291.600 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.75 637.85 Td +(IO42) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 641.45 Td +(35) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 640.800 m +291.600 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +271.48 645.05 Td +(RXD0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 648.65 Td +(36) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 648.000 m +291.600 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +272.21 652.25 Td +(TXD0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 655.85 Td +(37) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 655.200 m +291.600 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +278.38 659.45 Td +(IO2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 663.05 Td +(38) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 662.400 m +291.600 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +278.38 666.65 Td +(IO1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 670.25 Td +(39) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 669.600 m +291.600 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +274.39 673.85 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.96 677.45 Td +(40) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 676.800 m +291.600 676.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +275.62 685.37 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +291.60 688.25 Td +(41) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +298.800 687.600 m +291.600 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +169.20 739.31 Td +(U1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +190.80 570.11 Td +(ESP32-S3-WROOM-1-N16R8) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1062.00 504.00 61.20 -32.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1066.68 500.40 m 1066.68 501.00 1066.20 501.48 1065.60 501.48 c +1065.00 501.48 1064.52 501.00 1064.52 500.40 c +1064.52 499.80 1065.00 499.32 1065.60 499.32 c +1066.20 499.32 1066.68 499.80 1066.68 500.40 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1064.66 493.85 Td +(CS#) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1058.00 497.45 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1054.800 496.800 m +1062.000 496.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1064.66 486.65 Td +(DO/IO1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1058.00 490.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1054.800 489.600 m +1062.000 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1064.66 479.45 Td +(WP#/IO2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1058.00 483.05 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1054.800 482.400 m +1062.000 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1064.66 472.25 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1058.00 475.85 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1054.800 475.200 m +1062.000 475.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1104.28 472.91 Td +(DI/IO0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1123.56 475.85 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1130.400 475.200 m +1123.200 475.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1110.47 480.11 Td +(CLK) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1123.56 483.05 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1130.400 482.400 m +1123.200 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1061.73 487.31 Td +(HOLD#/RESET#/IO3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1123.56 490.25 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1130.400 489.600 m +1123.200 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1109.38 494.51 Td +(VCC) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1123.56 497.45 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1130.400 496.800 m +1123.200 496.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1062.00 505.31 Td +(U6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1076.40 505.31 Td +(W25Q16JVSNIQ) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 591.60 Td +(GPIO7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 594.37 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 594.000 m +874.800 594.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 598.80 Td +(GPIO6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 601.57 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 601.200 m +874.800 601.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 606.00 Td +(GPIO5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 608.77 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 608.400 m +874.800 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 613.20 Td +(GPIO4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 615.97 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 615.600 m +874.800 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 793.39 415.87 Tm +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 790.62 406.51 Tm +(57) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +792.000 406.800 m +792.000 414.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 638.40 Td +(QSPI_SS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 641.17 Td +(56) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 640.800 m +709.200 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 620.40 Td +(QSPI_SD1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 623.17 Td +(55) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 622.800 m +709.200 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 613.20 Td +(QSPI_SD2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 615.97 Td +(54) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 615.600 m +709.200 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 627.60 Td +(QSPI_SD0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 630.37 Td +(53) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 630.000 m +709.200 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 595.20 Td +(QSPI_SCLK) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 597.97 Td +(52) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 597.600 m +709.200 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 606.00 Td +(QSPI_SD3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 608.77 Td +(51) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 608.400 m +709.200 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 735.79 665.17 Tm +(DVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 733.02 685.79 Tm +(50) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +734.400 694.800 m +734.400 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 620.40 Td +(GPIO3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 623.17 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 622.800 m +874.800 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 782.59 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 779.82 685.79 Tm +(49) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +781.200 694.800 m +781.200 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 829.39 652.80 Tm +(USB_VDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 826.62 685.79 Tm +(48) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +828.000 694.800 m +828.000 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +845.73 670.80 Td +(USB_DP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 673.57 Td +(47) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 673.200 m +874.800 673.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +844.65 663.60 Td +(USB_DM) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 666.37 Td +(46) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 666.000 m +874.800 666.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 757.39 643.34 Tm +(VREG_VOUT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 754.62 685.79 Tm +(45) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 694.800 m +756.000 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 768.19 654.98 Tm +(VREG_IN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 765.42 685.79 Tm +(44) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +766.800 694.800 m +766.800 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 840.19 648.07 Tm +(ADC_AVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 837.42 685.79 Tm +(43) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +838.800 694.800 m +838.800 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 789.79 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 787.02 685.79 Tm +(42) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +788.400 694.800 m +788.400 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +827.18 426.00 Td +(GPIO29_ADC3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 428.77 Td +(41) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 428.400 m +874.800 428.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +879.120 431.280 m +884.880 425.520 l +879.120 425.520 m +884.880 431.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +827.18 433.20 Td +(GPIO28_ADC2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 435.97 Td +(40) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 435.600 m +874.800 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 627.60 Td +(GPIO2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 630.37 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 630.000 m +874.800 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +827.18 440.40 Td +(GPIO27_ADC1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 443.17 Td +(39) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 442.800 m +874.800 442.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +827.18 447.60 Td +(GPIO26_ADC0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 450.37 Td +(38) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 450.000 m +874.800 450.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 462.00 Td +(GPIO25) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 464.77 Td +(37) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 464.400 m +874.800 464.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 469.20 Td +(GPIO24) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 471.97 Td +(36) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 471.600 m +874.800 471.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +879.120 474.480 m +884.880 468.720 l +879.120 468.720 m +884.880 474.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 476.40 Td +(GPIO23) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 479.17 Td +(35) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 478.800 m +874.800 478.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +879.120 481.680 m +884.880 475.920 l +879.120 475.920 m +884.880 481.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 483.60 Td +(GPIO22) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 486.37 Td +(34) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 486.000 m +874.800 486.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 796.99 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 794.22 685.79 Tm +(33) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +795.600 694.800 m +795.600 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 490.80 Td +(GPIO21) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 493.57 Td +(32) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 493.200 m +874.800 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 498.00 Td +(GPIO20) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 500.77 Td +(31) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 500.400 m +874.800 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 505.20 Td +(GPIO19) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 507.97 Td +(30) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 507.600 m +874.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 634.80 Td +(GPIO1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 637.57 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 637.200 m +874.800 637.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 512.40 Td +(GPIO18) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 515.17 Td +(29) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 514.800 m +874.800 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 519.60 Td +(GPIO17) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 522.37 Td +(28) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 522.000 m +874.800 522.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 526.80 Td +(GPIO16) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 529.57 Td +(27) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 529.200 m +874.800 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 490.80 Td +(RUN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 493.57 Td +(26) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 493.200 m +709.200 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 451.20 Td +(SWD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 453.97 Td +(25) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 453.600 m +709.200 453.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 458.40 Td +(SWCLK) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 461.17 Td +(24) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 460.800 m +709.200 460.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 742.99 665.17 Tm +(DVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 740.22 685.79 Tm +(23) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +741.600 694.800 m +741.600 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 804.19 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 801.42 685.79 Tm +(22) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +802.800 694.800 m +802.800 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 526.80 Td +(XOUT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 529.57 Td +(21) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 529.200 m +709.200 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +712.08 541.20 Td +(XIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +702.72 543.97 Td +(20) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +702.000 543.600 m +709.200 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 642.00 Td +(GPIO0) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +877.64 644.77 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 644.400 m +874.800 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 757.39 415.87 Tm +(TESTEN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 754.62 406.51 Tm +(19) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 406.800 m +756.000 414.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 534.00 Td +(GPIO15) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 536.77 Td +(18) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 536.400 m +874.800 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 541.20 Td +(GPIO14) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 543.97 Td +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 543.600 m +874.800 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 548.40 Td +(GPIO13) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 551.17 Td +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 550.800 m +874.800 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 555.60 Td +(GPIO12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 558.37 Td +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 558.000 m +874.800 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 562.80 Td +(GPIO11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 565.57 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 565.200 m +874.800 565.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +848.27 570.00 Td +(GPIO10) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 572.77 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 572.400 m +874.800 572.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 577.20 Td +(GPIO9) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 579.97 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 579.600 m +874.800 579.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +851.91 584.40 Td +(GPIO8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +874.00 587.17 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +882.000 586.800 m +874.800 586.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 811.39 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 808.62 685.79 Tm +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +810.000 694.800 m +810.000 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 818.59 662.98 Tm +(IOVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 815.82 689.43 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 694.800 m +817.200 687.600 l +S +7.20 w +BT +/F2 10.454543999999999 Tf +11.50 TL +0.627 0.000 0.000 rg +773.11 545.15 Td +(RP2040) Tj +ET +7.20 w +BT +/F2 10.454543999999999 Tf +11.50 TL +0.627 0.000 0.000 rg +761.79 559.55 Td +(Raspberry Pi) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +709.20 687.60 165.60 -273.60 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +694.80 667.31 Td +(U7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +709.20 397.31 Td +(RP2040) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1058.40 608.40 57.60 -28.80 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1061.06 598.25 Td +(VIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1054.40 601.85 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1051.200 601.200 m +1058.400 601.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1061.06 591.05 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1054.40 594.65 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1051.200 594.000 m +1058.400 594.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1061.06 583.85 Td +(EN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1054.40 587.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1051.200 586.800 m +1058.400 586.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1103.88 583.85 Td +(NC) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1116.36 587.45 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1123.200 586.800 m +1116.000 586.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +1120.320 589.680 m +1126.080 583.920 l +1120.320 583.920 m +1126.080 589.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1095.15 598.25 Td +(VOUT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1116.36 601.85 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1123.200 601.200 m +1116.000 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1063.08 604.80 m 1063.08 605.40 1062.60 605.88 1062.00 605.88 c +1061.40 605.88 1060.92 605.40 1060.92 604.80 c +1060.92 604.20 1061.40 603.72 1062.00 603.72 c +1062.60 603.72 1063.08 604.20 1063.08 604.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1058.40 609.71 Td +(U8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1058.40 570.11 Td +(MIC5504-3.3YM5-TR) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 543.600 m +1162.800 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 572.400 m +1162.800 565.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1153.440 546.480 m +1154.880 549.360 l +1156.320 547.920 l +1153.440 546.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1150.560 549.360 m +1152.000 552.240 l +1153.440 550.800 l +1150.560 549.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1158.480 551.520 m +1155.600 548.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1155.600 554.400 m +1152.720 551.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1162.800 554.400 m +1162.800 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1162.800 565.200 m +1162.800 561.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1157.760 554.400 m +1167.840 554.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1157.760 561.600 m +1162.800 554.400 l +1167.840 561.600 l +1157.760 561.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1170.00 559.31 Td +(LED1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +941.040 395.280 m +942.480 398.160 l +943.920 396.720 l +941.040 395.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +938.160 398.160 m +939.600 401.040 l +941.040 399.600 l +938.160 398.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +946.080 400.320 m +943.200 397.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +943.200 403.200 m +940.320 400.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +950.400 403.200 m +950.400 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +950.400 414.000 m +950.400 410.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +945.360 403.200 m +955.440 403.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +945.360 410.400 m +950.400 403.200 l +955.440 410.400 l +945.360 410.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +950.400 392.400 m +950.400 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +950.400 421.200 m +950.400 414.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +957.60 407.68 Td +(LED2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +892.80 386.51 Td +(SML-D12D8WT86) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +950.400 457.200 m +950.400 450.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +950.400 428.400 m +950.400 435.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +947.52 450.00 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +957.60 444.11 Td +(R7) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +957.60 436.91 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +997.200 604.800 m +997.200 608.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +993.600 612.000 m +1000.800 612.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +997.200 612.000 m +997.200 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +995.49 616.91 Td +(VBUS) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 604.800 m +1029.600 608.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1026.000 612.000 m +1033.200 612.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1029.600 612.000 m +1029.600 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1020.87 613.31 Td +(VSYS) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1141.200 601.200 m +1141.200 604.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1137.600 608.400 m +1144.800 608.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1141.200 608.400 m +1141.200 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1135.38 609.71 Td +(3V3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 601.200 m +1162.800 594.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 572.400 m +1162.800 579.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1159.92 594.00 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1170.00 588.11 Td +(R8) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +1170.00 580.91 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1087.200 558.000 m +1087.200 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1080.000 550.800 m +1094.400 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1086.480 544.320 m +1087.920 544.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1084.320 546.480 m +1090.080 546.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1082.160 548.640 m +1092.240 548.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1079.93 537.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.400 543.600 m +1141.200 543.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1141.200 550.800 m +1141.200 536.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1134.720 544.320 m +1134.720 542.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1136.880 546.480 m +1136.880 540.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1139.040 548.640 m +1139.040 538.560 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1132.69 536.33 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1000.800 601.200 m +997.200 601.200 l +S +997.200 604.800 m +997.200 601.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1000.800 601.200 m +997.200 601.200 l +S +997.200 604.800 m +997.200 601.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 601.200 m +1029.600 604.800 l +S +1029.600 594.000 m +1029.600 601.200 l +S +1029.600 601.200 m +1033.200 601.200 l +S +1033.200 586.800 m +1033.200 601.200 l +S +1051.200 586.800 m +1033.200 586.800 l +S +1033.200 601.200 m +1051.200 601.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 601.200 m +1029.600 604.800 l +S +1029.600 594.000 m +1029.600 601.200 l +S +1029.600 601.200 m +1033.200 601.200 l +S +1033.200 586.800 m +1033.200 601.200 l +S +1051.200 586.800 m +1033.200 586.800 l +S +1033.200 601.200 m +1051.200 601.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1087.200 558.000 m +1087.200 565.200 l +S +1087.200 565.200 m +1134.000 565.200 l +S +1134.000 565.200 m +1134.000 572.400 l +S +1087.200 565.200 m +1044.000 565.200 l +S +1044.000 565.200 m +1029.600 565.200 l +S +1044.000 565.200 m +1044.000 594.000 l +S +1044.000 594.000 m +1051.200 594.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1087.200 558.000 m +1087.200 565.200 l +S +1087.200 565.200 m +1134.000 565.200 l +S +1134.000 565.200 m +1134.000 572.400 l +S +1087.200 565.200 m +1044.000 565.200 l +S +1044.000 565.200 m +1029.600 565.200 l +S +1044.000 565.200 m +1044.000 594.000 l +S +1044.000 594.000 m +1051.200 594.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1123.200 601.200 m +1134.000 601.200 l +S +1134.000 601.200 m +1141.200 601.200 l +S +1162.800 601.200 m +1141.200 601.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1123.200 601.200 m +1134.000 601.200 l +S +1134.000 601.200 m +1141.200 601.200 l +S +1162.800 601.200 m +1141.200 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 496.800 m +1170.000 500.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1166.400 504.000 m +1173.600 504.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1170.000 504.000 m +1170.000 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1164.18 505.31 Td +(3V3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 457.200 m +1170.000 450.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1162.800 450.000 m +1177.200 450.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1169.280 443.520 m +1170.720 443.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1167.120 445.680 m +1172.880 445.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1164.960 447.840 m +1175.040 447.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1162.73 436.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1170.000 496.800 m +1130.400 496.800 l +S +1170.000 496.800 m +1170.000 486.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1170.000 496.800 m +1130.400 496.800 l +S +1170.000 496.800 m +1170.000 486.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1054.800 475.200 m +1047.600 475.200 l +S +1047.600 457.200 m +1047.600 475.200 l +S +1047.600 457.200 m +1170.000 457.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1054.800 475.200 m +1047.600 475.200 l +S +1047.600 457.200 m +1047.600 475.200 l +S +1047.600 457.200 m +1170.000 457.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1022.40 498.11 Td +(QSPI_SS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +997.200 496.800 m +1054.800 496.800 l +S +997.200 493.200 m +997.200 496.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1022.40 498.11 Td +(QSPI_SS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +997.200 496.800 m +1054.800 496.800 l +S +997.200 493.200 m +997.200 496.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1026.00 490.91 Td +(QSPI_SD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1026.000 489.600 m +1054.800 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1026.00 490.91 Td +(QSPI_SD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1026.000 489.600 m +1054.800 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1026.00 483.71 Td +(QSPI_SD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1026.000 482.400 m +1054.800 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1026.00 483.71 Td +(QSPI_SD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1026.000 482.400 m +1054.800 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1127.19 490.91 Td +(QSPI_SD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 489.600 m +1159.200 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1127.19 490.91 Td +(QSPI_SD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 489.600 m +1159.200 489.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1126.42 483.71 Td +(QSPI_SCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 482.400 m +1162.800 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1126.42 483.71 Td +(QSPI_SCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 482.400 m +1162.800 482.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1127.19 476.51 Td +(QSPI_SD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 475.200 m +1159.200 475.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1127.19 476.51 Td +(QSPI_SD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1130.400 475.200 m +1159.200 475.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +997.200 493.200 m +997.200 486.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +997.200 464.400 m +997.200 471.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +994.32 486.00 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1004.40 483.71 Td +(R9) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +1004.40 476.51 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 439.200 m +1044.000 439.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1044.000 432.000 m +1044.000 446.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1050.480 438.480 m +1050.480 439.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1048.320 436.320 m +1048.320 442.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1046.160 434.160 m +1046.160 444.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1043.93 447.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 464.400 m +1000.800 464.400 l +S +1029.600 468.000 m +1029.600 464.400 l +S +1029.600 464.400 m +1029.600 457.200 l +S +1000.800 457.200 m +1000.800 464.400 l +S +997.200 464.400 m +1000.800 464.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 464.400 m +1000.800 464.400 l +S +1029.600 468.000 m +1029.600 464.400 l +S +1029.600 464.400 m +1029.600 457.200 l +S +1000.800 457.200 m +1000.800 464.400 l +S +997.200 464.400 m +1000.800 464.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 439.200 m +1036.800 439.200 l +S +1029.600 435.600 m +1029.600 439.200 l +S +1000.800 435.600 m +1029.600 435.600 l +S +1000.800 442.800 m +1000.800 435.600 l +S +1029.600 442.800 m +1029.600 439.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 439.200 m +1036.800 439.200 l +S +1029.600 435.600 m +1029.600 439.200 l +S +1000.800 435.600 m +1029.600 435.600 l +S +1000.800 442.800 m +1000.800 435.600 l +S +1029.600 442.800 m +1029.600 439.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +792.000 392.400 m +792.000 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +784.800 385.200 m +799.200 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +791.280 378.720 m +792.720 378.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +789.120 380.880 m +794.880 380.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +786.960 383.040 m +797.040 383.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +784.73 372.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +673.200 500.400 m +673.200 493.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +666.000 493.200 m +680.400 493.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +672.480 486.720 m +673.920 486.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +670.320 488.880 m +676.080 488.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +668.160 491.040 m +678.240 491.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +665.93 480.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +691.200 392.400 m +691.200 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +684.000 385.200 m +698.400 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +690.480 378.720 m +691.920 378.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +688.320 380.880 m +694.080 380.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +686.160 383.040 m +696.240 383.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +683.93 372.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 529.200 m +687.600 529.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 529.200 m +687.600 529.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +648.000 543.600 m +702.000 543.600 l +S +658.800 529.200 m +648.000 529.200 l +S +648.000 529.200 m +648.000 543.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +648.000 543.600 m +702.000 543.600 l +S +658.800 529.200 m +648.000 529.200 l +S +648.000 529.200 m +648.000 543.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +673.200 514.800 m +673.200 500.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +673.200 514.800 m +673.200 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +684.22 494.51 Td +(RUN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +691.200 435.600 m +691.200 446.400 l +S +655.200 446.400 m +691.200 446.400 l +S +655.200 435.600 m +655.200 446.400 l +S +655.200 435.600 m +662.400 435.600 l +S +691.200 493.200 m +691.200 446.400 l +S +691.200 493.200 m +702.000 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +684.22 494.51 Td +(RUN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +691.200 435.600 m +691.200 446.400 l +S +655.200 446.400 m +691.200 446.400 l +S +655.200 435.600 m +655.200 446.400 l +S +655.200 435.600 m +662.400 435.600 l +S +691.200 493.200 m +691.200 446.400 l +S +691.200 493.200 m +702.000 493.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +691.200 421.200 m +691.200 403.200 l +S +655.200 403.200 m +691.200 403.200 l +S +655.200 421.200 m +655.200 403.200 l +S +662.400 421.200 m +655.200 421.200 l +S +691.200 392.400 m +691.200 403.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +691.200 421.200 m +691.200 403.200 l +S +655.200 403.200 m +691.200 403.200 l +S +655.200 421.200 m +655.200 403.200 l +S +662.400 421.200 m +655.200 421.200 l +S +691.200 392.400 m +691.200 403.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +662.40 462.11 Td +(SWCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +662.400 460.800 m +702.000 460.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +662.40 462.11 Td +(SWCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +662.400 460.800 m +702.000 460.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +662.40 454.91 Td +(SWDIO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +662.400 453.600 m +702.000 453.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +662.40 454.91 Td +(SWDIO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +662.400 453.600 m +702.000 453.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +792.000 406.800 m +792.000 399.600 l +S +792.000 399.600 m +756.000 399.600 l +S +756.000 399.600 m +756.000 406.800 l +S +792.000 392.400 m +792.000 399.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +792.000 406.800 m +792.000 399.600 l +S +792.000 399.600 m +756.000 399.600 l +S +756.000 399.600 m +756.000 406.800 l +S +792.000 392.400 m +792.000 399.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 642.11 Td +(QSPI_SS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 640.800 m +702.000 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 642.11 Td +(QSPI_SS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 640.800 m +702.000 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 631.31 Td +(QSPI_SD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 630.000 m +655.200 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 631.31 Td +(QSPI_SD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 630.000 m +655.200 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 624.11 Td +(QSPI_SD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 622.800 m +655.200 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 624.11 Td +(QSPI_SD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +702.000 622.800 m +655.200 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 616.91 Td +(QSPI_SD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 615.600 m +702.000 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 616.91 Td +(QSPI_SD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 615.600 m +702.000 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 609.71 Td +(QSPI_SD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 608.400 m +702.000 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 609.71 Td +(QSPI_SD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 608.400 m +702.000 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 598.91 Td +(QSPI_SCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 597.600 m +702.000 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +655.20 598.91 Td +(QSPI_SCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +655.200 597.600 m +702.000 597.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +950.400 385.200 m +950.400 378.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +943.200 378.000 m +957.600 378.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +949.680 371.520 m +951.120 371.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +947.520 373.680 m +953.280 373.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +945.360 375.840 m +955.440 375.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +943.13 364.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +950.400 385.200 m +950.400 392.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +950.400 385.200 m +950.400 392.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +950.400 421.200 m +950.400 428.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +950.400 421.200 m +950.400 428.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +882.000 464.400 m +950.400 464.400 l +S +950.400 464.400 m +950.400 457.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +882.000 464.400 m +950.400 464.400 l +S +950.400 464.400 m +950.400 457.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 645.71 Td +(GPIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 644.400 m +882.000 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 645.71 Td +(GPIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 644.400 m +882.000 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 638.51 Td +(GPIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 637.200 m +882.000 637.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 638.51 Td +(GPIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 637.200 m +882.000 637.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 631.31 Td +(GPIO2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 630.000 m +882.000 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 631.31 Td +(GPIO2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 630.000 m +882.000 630.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 624.11 Td +(GPIO3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 622.800 m +882.000 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +890.79 624.11 Td +(GPIO3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 622.800 m +882.000 622.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 566.51 Td +(GPIO11) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 565.200 m +882.000 565.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 566.51 Td +(GPIO11) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 565.200 m +882.000 565.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 559.31 Td +(GPIO12) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 558.000 m +882.000 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 559.31 Td +(GPIO12) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 558.000 m +882.000 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 552.11 Td +(GPIO13) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 550.800 m +882.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 552.11 Td +(GPIO13) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 550.800 m +882.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 544.91 Td +(GPIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 543.600 m +882.000 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 544.91 Td +(GPIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 543.600 m +882.000 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 537.71 Td +(GPIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 536.400 m +882.000 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 537.71 Td +(GPIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 536.400 m +882.000 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 530.51 Td +(GPIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 529.200 m +882.000 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 530.51 Td +(GPIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 529.200 m +882.000 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 523.31 Td +(GPIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 522.000 m +882.000 522.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 523.31 Td +(GPIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 522.000 m +882.000 522.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 516.11 Td +(GPIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 514.800 m +882.000 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 516.11 Td +(GPIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 514.800 m +882.000 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 508.91 Td +(GPIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 507.600 m +882.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 508.91 Td +(GPIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 507.600 m +882.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 501.71 Td +(GPIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 500.400 m +882.000 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 501.71 Td +(GPIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 500.400 m +882.000 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 494.51 Td +(GPIO21) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 493.200 m +882.000 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 494.51 Td +(GPIO21) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 493.200 m +882.000 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 487.31 Td +(GPIO22) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 486.000 m +882.000 486.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 487.31 Td +(GPIO22) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 486.000 m +882.000 486.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 451.31 Td +(GPIO26) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 450.000 m +882.000 450.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 451.31 Td +(GPIO26) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 450.000 m +882.000 450.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 444.11 Td +(GPIO27) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 442.800 m +882.000 442.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 444.11 Td +(GPIO27) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 442.800 m +882.000 442.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 436.91 Td +(GPIO28) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 435.600 m +882.000 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +900.00 436.91 Td +(GPIO28) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 435.600 m +882.000 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +853.200 712.800 m +853.200 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +846.000 705.600 m +860.400 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +852.480 699.120 m +853.920 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +850.320 701.280 m +856.080 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +848.160 703.440 m +858.240 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +845.93 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +853.200 712.800 m +853.200 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +853.200 712.800 m +853.200 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 712.800 m +817.200 694.800 l +S +817.200 712.800 m +810.000 712.800 l +S +810.000 712.800 m +810.000 694.800 l +S +810.000 712.800 m +802.800 712.800 l +S +802.800 712.800 m +802.800 694.800 l +S +802.800 712.800 m +795.600 712.800 l +S +795.600 712.800 m +795.600 694.800 l +S +795.600 712.800 m +788.400 712.800 l +S +788.400 712.800 m +788.400 694.800 l +S +781.200 712.800 m +788.400 712.800 l +S +781.200 694.800 m +781.200 712.800 l +S +766.800 712.800 m +781.200 712.800 l +S +766.800 694.800 m +766.800 712.800 l +S +766.800 712.800 m +766.800 745.200 l +S +853.200 745.200 m +766.800 745.200 l +S +853.200 745.200 m +853.200 741.600 l +S +853.200 745.200 m +874.800 745.200 l +S +874.800 741.600 m +874.800 745.200 l +S +874.800 745.200 m +896.400 745.200 l +S +896.400 741.600 m +896.400 745.200 l +S +896.400 745.200 m +918.000 745.200 l +S +918.000 741.600 m +918.000 745.200 l +S +943.200 745.200 m +918.000 745.200 l +S +817.200 712.800 m +828.000 712.800 l +S +838.800 712.800 m +828.000 712.800 l +S +838.800 712.800 m +838.800 694.800 l +S +828.000 712.800 m +828.000 694.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 712.800 m +817.200 694.800 l +S +817.200 712.800 m +810.000 712.800 l +S +810.000 712.800 m +810.000 694.800 l +S +810.000 712.800 m +802.800 712.800 l +S +802.800 712.800 m +802.800 694.800 l +S +802.800 712.800 m +795.600 712.800 l +S +795.600 712.800 m +795.600 694.800 l +S +795.600 712.800 m +788.400 712.800 l +S +788.400 712.800 m +788.400 694.800 l +S +781.200 712.800 m +788.400 712.800 l +S +781.200 694.800 m +781.200 712.800 l +S +766.800 712.800 m +781.200 712.800 l +S +766.800 694.800 m +766.800 712.800 l +S +766.800 712.800 m +766.800 745.200 l +S +853.200 745.200 m +766.800 745.200 l +S +853.200 745.200 m +853.200 741.600 l +S +853.200 745.200 m +874.800 745.200 l +S +874.800 741.600 m +874.800 745.200 l +S +874.800 745.200 m +896.400 745.200 l +S +896.400 741.600 m +896.400 745.200 l +S +896.400 745.200 m +918.000 745.200 l +S +918.000 741.600 m +918.000 745.200 l +S +943.200 745.200 m +918.000 745.200 l +S +817.200 712.800 m +828.000 712.800 l +S +838.800 712.800 m +828.000 712.800 l +S +838.800 712.800 m +838.800 694.800 l +S +828.000 712.800 m +828.000 694.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +741.600 712.800 m +756.000 712.800 l +S +756.000 712.800 m +756.000 694.800 l +S +756.000 712.800 m +756.000 745.200 l +S +716.400 745.200 m +756.000 745.200 l +S +716.400 745.200 m +716.400 741.600 l +S +716.400 745.200 m +698.400 745.200 l +S +698.400 745.200 m +698.400 741.600 l +S +651.600 745.200 m +698.400 745.200 l +S +741.600 712.800 m +734.400 712.800 l +S +734.400 694.800 m +734.400 712.800 l +S +741.600 712.800 m +741.600 694.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +741.600 712.800 m +756.000 712.800 l +S +756.000 712.800 m +756.000 694.800 l +S +756.000 712.800 m +756.000 745.200 l +S +716.400 745.200 m +756.000 745.200 l +S +716.400 745.200 m +716.400 741.600 l +S +716.400 745.200 m +698.400 745.200 l +S +698.400 745.200 m +698.400 741.600 l +S +651.600 745.200 m +698.400 745.200 l +S +741.600 712.800 m +734.400 712.800 l +S +734.400 694.800 m +734.400 712.800 l +S +741.600 712.800 m +741.600 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +716.400 712.800 m +716.400 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +709.200 705.600 m +723.600 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +715.680 699.120 m +717.120 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +713.520 701.280 m +719.280 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +711.360 703.440 m +721.440 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +709.13 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +716.400 712.800 m +716.400 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +716.400 712.800 m +716.400 712.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +943.200 745.200 m +943.200 748.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +939.600 752.400 m +946.800 752.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +943.200 752.400 m +943.200 748.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +937.38 753.71 Td +(3V3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +651.600 745.200 m +651.600 748.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +648.000 752.400 m +655.200 752.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +651.600 752.400 m +651.600 748.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +645.78 753.71 Td +(1V1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +895.41 674.51 Td +(USB_DP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +921.600 673.200 m +882.000 673.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +895.41 674.51 Td +(USB_DP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +921.600 673.200 m +882.000 673.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +894.33 667.31 Td +(USB_DM) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +921.600 666.000 m +882.000 666.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +894.33 667.31 Td +(USB_DM) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +921.600 666.000 m +882.000 666.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +874.800 712.800 m +874.800 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +867.600 705.600 m +882.000 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +874.080 699.120 m +875.520 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +871.920 701.280 m +877.680 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +869.760 703.440 m +879.840 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +867.53 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 712.800 m +896.400 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +889.200 705.600 m +903.600 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +895.680 699.120 m +897.120 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +893.520 701.280 m +899.280 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +891.360 703.440 m +901.440 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +889.13 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +918.000 712.800 m +918.000 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +910.800 705.600 m +925.200 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +917.280 699.120 m +918.720 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +915.120 701.280 m +920.880 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +912.960 703.440 m +923.040 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +910.73 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 712.800 m +698.400 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +691.200 705.600 m +705.600 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +697.680 699.120 m +699.120 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +695.520 701.280 m +701.280 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +693.360 703.440 m +703.440 703.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +691.13 692.51 Td +(GND) Tj +ET +7.20 w +BT +/F2 22.909090909090903 Tf +25.20 TL +0.000 g +745.20 753.38 Td +(RP2040) Tj +ET +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1047.60 621.82 Td +(3.3V Regulator) Tj +ET +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1069.20 438.22 Td +(Flash Memory) Tj +ET +7.20 w +BT +/F2 4.581818181818181 Tf +5.04 TL +0.000 g +1004.40 465.32 Td +(Boot Switch) Tj +ET +7.20 w +BT +/F2 5.153901216893343 Tf +5.67 TL +0.000 g +658.80 415.03 Td +(Run Switch) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1029.600 578.160 m +1029.600 572.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 594.000 m +1029.600 586.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1023.840 581.040 m +1035.360 581.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1029.600 586.800 m +1029.600 581.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 565.200 m +1029.600 572.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1035.360 578.160 m +1023.840 578.160 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +1040.40 580.48 Td +(C1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1040.40 573.71 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1134.000 585.360 m +1134.000 579.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1134.000 601.200 m +1134.000 594.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1128.240 588.240 m +1139.760 588.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1134.000 594.000 m +1134.000 588.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1134.000 572.400 m +1134.000 579.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1139.760 585.360 m +1128.240 585.360 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +1144.80 587.68 Td +(C11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1144.80 580.91 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1170.000 470.160 m +1170.000 464.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 486.000 m +1170.000 478.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1164.240 473.040 m +1175.760 473.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1170.000 478.800 m +1170.000 473.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 457.200 m +1170.000 464.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1175.760 470.160 m +1164.240 470.160 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +1173.60 476.08 Td +(C12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1173.60 462.11 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +853.200 725.760 m +853.200 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +853.200 741.600 m +853.200 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +847.440 728.640 m +858.960 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +853.200 734.400 m +853.200 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +853.200 712.800 m +853.200 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +858.960 725.760 m +847.440 725.760 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +849.60 760.48 Td +(C4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +849.60 750.11 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +716.400 725.760 m +716.400 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +716.400 741.600 m +716.400 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +710.640 728.640 m +722.160 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +716.400 734.400 m +716.400 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +716.400 712.800 m +716.400 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +722.160 725.760 m +710.640 725.760 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +712.80 764.08 Td +(C5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +712.80 753.71 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 712.800 m +698.400 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 712.800 m +698.400 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +874.800 712.800 m +874.800 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +874.800 712.800 m +874.800 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 712.800 m +896.400 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 712.800 m +896.400 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +918.000 712.800 m +918.000 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +918.000 712.800 m +918.000 712.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 573.71 Td +(GPIO10) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 572.400 m +882.000 572.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +887.15 573.71 Td +(GPIO10) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 572.400 m +882.000 572.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 442.800 m +1015.200 447.120 l +1012.320 452.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 457.200 m +1015.200 452.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.000 442.800 m +1022.400 442.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.000 457.200 m +1022.400 457.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1020.960 457.200 m +1022.400 457.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1004.36 457.85 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1000.800 457.200 m +1008.000 457.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1022.40 457.85 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 457.200 m +1022.400 457.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1022.40 443.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 442.800 m +1022.400 442.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1004.36 443.45 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1000.800 442.800 m +1008.000 442.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1018.80 451.31 Td +(SW1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +676.800 421.200 m +676.800 425.520 l +673.920 431.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +676.800 435.600 m +676.800 431.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +669.600 421.200 m +684.000 421.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +669.600 435.600 m +684.000 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +682.560 435.600 m +684.000 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +665.96 436.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +662.400 435.600 m +669.600 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +684.00 436.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +691.200 435.600 m +684.000 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +684.00 421.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +691.200 421.200 m +684.000 421.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +665.96 421.85 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +662.400 421.200 m +669.600 421.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +669.60 440.51 Td +(SW2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1000.800 601.200 m +1008.000 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 601.200 m +1022.400 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1020.240 604.800 m +1020.240 606.240 l +1018.800 606.240 l +1018.800 596.160 l +1017.360 596.160 l +1017.360 597.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.000 601.200 m +1011.600 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1018.800 601.200 m +1022.400 601.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1011.600 606.240 m +1018.800 601.200 l +1011.600 596.160 l +1011.600 606.240 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +1008.00 609.28 Td +(D1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1004.40 588.11 Td +(DSK34) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +676.800 524.160 m +676.800 534.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +687.600 529.200 m +680.400 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +680.400 529.200 m +676.800 529.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +671.76 534.24 2.88 -10.08 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +666.000 529.200 m +669.600 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +669.600 524.160 m +669.600 534.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +658.800 529.200 m +666.000 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +673.200 514.800 m +673.200 522.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +644.40 516.11 Td +(X1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +644.40 505.31 Td +(12MHz) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +902.160 725.760 m +890.640 725.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 712.800 m +896.400 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +896.400 734.400 m +896.400 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +890.640 728.640 m +902.160 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 741.600 m +896.400 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +896.400 725.760 m +896.400 720.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +892.80 760.48 Td +(C6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +892.80 750.11 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +923.760 725.760 m +912.240 725.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +918.000 712.800 m +918.000 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +918.000 734.400 m +918.000 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +912.240 728.640 m +923.760 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +918.000 741.600 m +918.000 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +918.000 725.760 m +918.000 720.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +918.00 760.48 Td +(C7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +918.00 750.11 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +880.560 725.760 m +869.040 725.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +874.800 712.800 m +874.800 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +874.800 734.400 m +874.800 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +869.040 728.640 m +880.560 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +874.800 741.600 m +874.800 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +874.800 725.760 m +874.800 720.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +874.80 760.48 Td +(C8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +871.20 750.11 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +704.160 725.760 m +692.640 725.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 712.800 m +698.400 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.400 734.400 m +698.400 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +692.640 728.640 m +704.160 728.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 741.600 m +698.400 734.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.400 725.760 m +698.400 720.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +698.40 760.48 Td +(C9) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +691.20 750.11 Td +(100nF) Tj +ET +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +640.80 781.20 345.60 -424.80 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.60 759.60 36.00 -93.60 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1048.39 670.25 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 673.85 Td +(A1B12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 673.200 m +1065.600 673.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1045.11 677.45 Td +(VBUS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 681.05 Td +(A4B9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 680.400 m +1065.600 680.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1045.84 684.65 Td +(SBU2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 688.25 Td +(B8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 687.600 m +1065.600 687.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +1069.920 690.480 m +1075.680 684.720 l +1069.920 684.720 m +1075.680 690.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1049.85 691.85 Td +(CC1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 695.45 Td +(A5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 694.800 m +1065.600 694.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1049.85 699.05 Td +(DN2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 702.65 Td +(B7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 702.000 m +1065.600 702.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1050.21 706.25 Td +(DP1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 709.85 Td +(A6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 709.200 m +1065.600 709.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1049.85 713.45 Td +(DN1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 717.05 Td +(A7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 716.400 m +1065.600 716.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1050.21 720.65 Td +(DP2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 724.25 Td +(B6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 723.600 m +1065.600 723.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1045.84 727.85 Td +(SBU1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 731.45 Td +(A8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 730.800 m +1065.600 730.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +1069.920 733.680 m +1075.680 727.920 l +1069.920 727.920 m +1075.680 733.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1049.85 735.05 Td +(CC2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 738.65 Td +(B5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 738.000 m +1065.600 738.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1045.11 742.25 Td +(VBUS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 745.85 Td +(B4A9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 745.200 m +1065.600 745.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1048.39 749.45 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1065.96 753.05 Td +(B1A12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1072.800 752.400 m +1065.600 752.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1031.04 728.57 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1025.96 731.45 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 730.800 m +1029.600 730.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1031.04 735.77 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1025.96 738.65 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 738.000 m +1029.600 738.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1031.04 742.97 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1025.96 745.85 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 745.200 m +1029.600 745.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1031.04 750.17 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1025.96 753.05 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 752.400 m +1029.600 752.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1029.60 760.91 Td +(PICOUSB) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 660.11 Td +(TYPE-C-31-M-12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1094.40 746.51 Td +(VBUS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1137.600 680.400 m +1137.600 745.200 l +S +1072.800 680.400 m +1137.600 680.400 l +S +1137.600 745.200 m +1072.800 745.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1094.40 746.51 Td +(VBUS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1137.600 680.400 m +1137.600 745.200 l +S +1072.800 680.400 m +1137.600 680.400 l +S +1137.600 745.200 m +1072.800 745.200 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1094.40 654.22 Td +(USB-C - Pico) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1141.200 694.800 m +1148.400 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 694.800 m +1162.800 694.800 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.40 697.68 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1148.40 699.71 Td +(R11) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +1148.40 685.31 Td +/F2 6.545454545454544 Tf +(5.1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1141.200 738.000 m +1148.400 738.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1170.000 738.000 m +1162.800 738.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1148.40 740.88 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1148.40 742.91 Td +(R12) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +1148.40 728.51 Td +/F2 6.545454545454544 Tf +(5.1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1141.200 738.000 m +1072.800 738.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1141.200 738.000 m +1072.800 738.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1141.200 694.800 m +1072.800 694.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1141.200 694.800 m +1072.800 694.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1108.80 710.51 Td +(USB_DP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1087.200 709.200 m +1072.800 709.200 l +S +1087.200 709.200 m +1087.200 723.600 l +S +1072.800 723.600 m +1087.200 723.600 l +S +1108.800 709.200 m +1087.200 709.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1108.80 710.51 Td +(USB_DP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1087.200 709.200 m +1072.800 709.200 l +S +1087.200 709.200 m +1087.200 723.600 l +S +1072.800 723.600 m +1087.200 723.600 l +S +1108.800 709.200 m +1087.200 709.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1108.80 717.71 Td +(USB_DM) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1080.000 716.400 m +1072.800 716.400 l +S +1080.000 702.000 m +1080.000 716.400 l +S +1072.800 702.000 m +1080.000 702.000 l +S +1108.800 716.400 m +1080.000 716.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1108.80 717.71 Td +(USB_DM) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1080.000 716.400 m +1072.800 716.400 l +S +1080.000 702.000 m +1080.000 716.400 l +S +1072.800 702.000 m +1080.000 702.000 l +S +1108.800 716.400 m +1080.000 716.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1121.40 674.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1072.800 752.400 m +1170.000 752.400 l +S +1170.000 752.400 m +1170.000 738.000 l +S +1170.000 694.800 m +1170.000 738.000 l +S +1170.000 673.200 m +1170.000 694.800 l +S +1072.800 673.200 m +1170.000 673.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1121.40 674.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1072.800 752.400 m +1170.000 752.400 l +S +1170.000 752.400 m +1170.000 738.000 l +S +1170.000 694.800 m +1170.000 738.000 l +S +1170.000 673.200 m +1170.000 694.800 l +S +1072.800 673.200 m +1170.000 673.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 752.400 m +1015.200 752.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 759.600 m +1015.200 745.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.720 753.120 m +1008.720 751.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1010.880 755.280 m +1010.880 749.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1013.040 757.440 m +1013.040 747.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1006.69 745.13 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 752.400 m +1022.400 752.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 752.400 m +1022.400 752.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 745.200 m +1015.200 745.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 752.400 m +1015.200 738.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.720 745.920 m +1008.720 744.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1010.880 748.080 m +1010.880 742.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1013.040 750.240 m +1013.040 740.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1006.69 737.93 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 745.200 m +1022.400 745.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 745.200 m +1022.400 745.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 738.000 m +1015.200 738.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 745.200 m +1015.200 730.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.720 738.720 m +1008.720 737.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1010.880 740.880 m +1010.880 735.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1013.040 743.040 m +1013.040 732.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1006.69 730.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 738.000 m +1022.400 738.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 738.000 m +1022.400 738.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 730.800 m +1015.200 730.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1015.200 738.000 m +1015.200 723.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1008.720 731.520 m +1008.720 730.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1010.880 733.680 m +1010.880 727.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1013.040 735.840 m +1013.040 725.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1006.69 723.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 730.800 m +1022.400 730.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 730.800 m +1022.400 730.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +144.000 676.800 m +144.000 684.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +151.200 684.000 m +136.800 684.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +144.720 690.480 m +143.280 690.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +146.880 688.320 m +141.120 688.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +149.040 686.160 m +138.960 686.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +136.73 692.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 676.800 m +144.000 676.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 676.800 m +144.000 676.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.600 687.600 m +327.600 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +334.800 694.800 m +320.400 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +328.320 701.280 m +326.880 701.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +330.480 699.120 m +324.720 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +332.640 696.960 m +322.560 696.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +320.33 703.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 687.600 m +327.600 687.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 687.600 m +327.600 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +144.00 670.91 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 669.600 m +144.000 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +144.00 670.91 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 669.600 m +144.000 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 0.000 rg +144.00 663.71 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 662.400 m +144.000 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 0.000 rg +144.00 663.71 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 662.400 m +144.000 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 656.51 Td +(MICWS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 655.200 m +144.000 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 656.51 Td +(MICWS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 655.200 m +144.000 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 649.31 Td +(MICSCK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 648.000 m +144.000 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 649.31 Td +(MICSCK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 648.000 m +144.000 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 642.11 Td +(MICSD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 640.800 m +144.000 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +144.00 642.11 Td +(MICSD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 640.800 m +144.000 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 634.91 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 633.600 m +144.000 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 634.91 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 633.600 m +144.000 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 627.71 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 626.400 m +144.000 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 627.71 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 626.400 m +144.000 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 620.51 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 619.200 m +144.000 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.200 rg +144.00 620.51 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 619.200 m +144.000 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +133.20 613.31 Td +(EIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 612.000 m +133.200 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +133.20 613.31 Td +(EIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 612.000 m +133.200 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +133.20 606.11 Td +(EIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 604.800 m +133.200 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +133.20 606.11 Td +(EIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 604.800 m +133.200 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +144.00 598.91 Td +(CAMD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 597.600 m +144.000 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +144.00 598.91 Td +(CAMD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 597.600 m +144.000 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +144.00 591.71 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 590.400 m +144.000 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +144.00 591.71 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 590.400 m +144.000 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +144.00 584.51 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 583.200 m +144.000 583.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +144.00 584.51 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +176.400 583.200 m +144.000 583.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 200.29 507.60 Tm +(EIO3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +201.600 543.600 m +201.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 200.29 507.60 Tm +(EIO3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +201.600 543.600 m +201.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 214.69 507.60 Tm +(CAMD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +216.000 543.600 m +216.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 214.69 507.60 Tm +(CAMD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +216.000 543.600 m +216.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 207.49 507.60 Tm +(EIO46) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +208.800 543.600 m +208.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 207.49 507.60 Tm +(EIO46) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +208.800 543.600 m +208.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 221.89 507.60 Tm +(CAMD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +223.200 543.600 m +223.200 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 221.89 507.60 Tm +(CAMD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +223.200 543.600 m +223.200 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 229.09 507.60 Tm +(CAMD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +230.400 507.600 m +230.400 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 229.09 507.60 Tm +(CAMD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +230.400 507.600 m +230.400 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 236.29 507.60 Tm +(CAMD4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +237.600 543.600 m +237.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 236.29 507.60 Tm +(CAMD4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +237.600 543.600 m +237.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 243.49 507.60 Tm +(CAMPCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +244.800 543.600 m +244.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 243.49 507.60 Tm +(CAMPCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +244.800 543.600 m +244.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 250.69 507.60 Tm +(EIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +252.000 543.600 m +252.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 250.69 507.60 Tm +(EIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +252.000 543.600 m +252.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 257.89 507.60 Tm +(CAMXCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +259.200 543.600 m +259.200 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 257.89 507.60 Tm +(CAMXCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +259.200 543.600 m +259.200 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 265.09 507.60 Tm +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +266.400 543.600 m +266.400 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 265.09 507.60 Tm +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +266.400 543.600 m +266.400 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 272.29 507.60 Tm +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +273.600 543.600 m +273.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +0.00 1.00 -1.00 0.00 272.29 507.60 Tm +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +273.600 543.600 m +273.600 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 279.49 507.60 Tm +(EIO45) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +280.800 543.600 m +280.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 279.49 507.60 Tm +(EIO45) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +280.800 543.600 m +280.800 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.86 678.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 676.800 m +338.400 676.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.86 678.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 676.800 m +338.400 676.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 670.91 Td +(EIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 669.600 m +338.400 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 670.91 Td +(EIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 669.600 m +338.400 669.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 663.71 Td +(EIO2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 662.400 m +338.400 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 663.71 Td +(EIO2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 662.400 m +338.400 662.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +318.76 656.51 Td +(EIOTX) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 655.200 m +338.400 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +318.76 656.51 Td +(EIOTX) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 655.200 m +338.400 655.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +318.03 649.31 Td +(EIORX) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 648.000 m +338.400 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +318.03 649.31 Td +(EIORX) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 648.000 m +338.400 648.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 1.000 rg +310.40 642.11 Td +(MONSCL) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 640.800 m +338.400 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 1.000 rg +310.40 642.11 Td +(MONSCL) Tj +ET +1 J +1 j +0.72 w +1.00 0.40 0.00 RG +0.00 g +[] 0 d +298.800 640.800 m +338.400 640.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 1.000 rg +309.67 634.91 Td +(MONSDA) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 633.600 m +338.400 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.000 1.000 rg +309.67 634.91 Td +(MONSDA) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 633.600 m +338.400 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 627.71 Td +(CAMD6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 626.400 m +338.400 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 627.71 Td +(CAMD6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 626.400 m +338.400 626.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 620.51 Td +(CAMD5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 619.200 m +338.400 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 620.51 Td +(CAMD5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 619.200 m +338.400 619.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.000 rg +313.30 613.31 Td +(RGBPIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 612.000 m +338.400 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.400 0.000 rg +313.30 613.31 Td +(RGBPIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 612.000 m +338.400 612.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +306.04 606.11 Td +(CAMHREF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 604.800 m +338.400 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +306.04 606.11 Td +(CAMHREF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 604.800 m +338.400 604.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +301.31 598.91 Td +(CAMVSYNC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 597.600 m +338.400 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +301.31 598.91 Td +(CAMVSYNC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 597.600 m +338.400 597.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 591.71 Td +(CAMD7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 590.400 m +338.400 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.400 0.800 0.200 rg +315.49 591.71 Td +(CAMD7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 590.400 m +338.400 590.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 584.51 Td +(EIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 583.200 m +338.400 583.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +323.48 584.51 Td +(EIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +298.800 583.200 m +338.400 583.200 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +36.00 781.20 406.80 -280.80 re +S +7.20 w +BT +/F2 19.636363636363633 Tf +21.60 TL +0.000 g +158.40 756.33 Td +(ESP32-S3 N16R8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +350.640 534.960 m +362.160 534.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +350.640 537.840 m +362.160 537.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +356.400 525.600 m +356.400 532.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +356.400 547.200 m +356.400 540.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +356.400 532.800 m +356.400 534.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +356.400 537.840 m +356.400 540.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +367.20 533.68 Td +(C13) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +367.20 519.71 Td +(16V) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +367.20 526.91 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +356.400 525.600 m +356.400 518.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +349.200 518.400 m +363.600 518.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +355.680 511.920 m +357.120 511.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +353.520 514.080 m +359.280 514.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +351.360 516.240 m +361.440 516.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +349.13 505.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 525.600 m +356.400 525.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 525.600 m +356.400 525.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +356.400 547.200 m +349.200 547.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +349.200 547.200 m +342.000 550.800 l +327.600 550.800 l +327.600 543.600 l +342.000 543.600 l +349.200 547.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +298.54 544.91 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 547.200 m +356.400 547.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 547.200 m +356.400 547.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +489.600 763.200 m +489.600 756.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +489.600 734.400 m +489.600 741.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +486.72 756.00 5.76 -14.40 re +S +7.20 w +BT +/F2 9.818181818181817 Tf +10.80 TL +0.000 0.000 0.502 rg +468.00 757.96 Td +(R13) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +468.00 750.11 Td +/F2 6.545454545454544 Tf +(10k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.200 759.600 m +565.200 752.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.200 730.800 m +565.200 738.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +562.32 752.40 5.76 -14.40 re +S +7.20 w +BT +/F2 9.818181818181817 Tf +10.80 TL +0.000 0.000 0.502 rg +572.40 743.56 Td +(R14) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +572.40 735.71 Td +/F2 6.545454545454544 Tf +(10k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +525.600 718.560 m +525.600 712.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +525.600 734.400 m +525.600 727.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +519.840 721.440 m +531.360 721.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +525.600 727.200 m +525.600 721.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +525.600 705.600 m +525.600 712.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +531.360 718.560 m +519.840 718.560 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +536.40 720.88 Td +(C14) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +536.40 714.11 Td +(1uF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +523.67 735.71 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +525.600 734.400 m +489.600 734.400 l +S +525.600 734.400 m +536.400 734.400 l +S +489.600 734.400 m +489.600 720.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +523.67 735.71 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +525.600 734.400 m +489.600 734.400 l +S +525.600 734.400 m +536.400 734.400 l +S +489.600 734.400 m +489.600 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +525.600 705.600 m +525.600 698.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +518.400 698.400 m +532.800 698.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +524.880 691.920 m +526.320 691.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +522.720 694.080 m +528.480 694.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +520.560 696.240 m +530.640 696.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +518.33 685.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +525.600 705.600 m +525.600 705.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +525.600 705.600 m +525.600 705.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +489.600 687.600 m +489.600 680.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +482.400 680.400 m +496.800 680.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +488.880 673.920 m +490.320 673.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +486.720 676.080 m +492.480 676.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +484.560 678.240 m +494.640 678.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +482.33 667.31 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +489.60 764.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +489.600 763.200 m +489.600 763.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +489.60 764.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +489.600 763.200 m +489.600 763.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +504.00 674.51 Td +(RESET) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +594.00 728.51 Td +(EIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 730.800 m +594.000 730.800 l +S +565.200 716.400 m +565.200 730.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +594.00 728.51 Td +(EIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 730.800 m +594.000 730.800 l +S +565.200 716.400 m +565.200 730.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +572.40 670.91 Td +(KEY_FLASH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +565.20 764.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 759.600 m +565.200 763.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +565.20 764.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 759.600 m +565.200 763.200 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +450.00 781.20 169.20 -140.40 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +525.60 650.62 Td +(Key) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +522.00 572.40 28.80 -28.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +526.68 568.80 m 526.68 569.40 526.20 569.88 525.60 569.88 c +525.00 569.88 524.52 569.40 524.52 568.80 c +524.52 568.20 525.00 567.72 525.60 567.72 c +526.20 567.72 526.68 568.20 526.68 568.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +524.66 562.25 Td +(G1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +518.00 565.85 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +514.800 565.200 m +522.000 565.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +524.66 555.05 Td +(S2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +518.00 558.65 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +514.800 558.000 m +522.000 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +524.66 547.85 Td +(G2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +518.00 551.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +514.800 550.800 m +522.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +539.77 547.85 Td +(D2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +551.16 551.45 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +558.000 550.800 m +550.800 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +540.13 555.05 Td +(S1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +551.16 558.65 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +558.000 558.000 m +550.800 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +539.77 562.25 Td +(D1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +551.16 565.85 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +558.000 565.200 m +550.800 565.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +518.40 530.51 Td +(Q1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +522.00 537.71 Td +(FDC6333C) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +500.400 583.200 m +500.400 590.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +500.400 612.000 m +500.400 604.800 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +497.52 604.80 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +507.60 598.91 Td +(R15) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +507.60 591.71 Td +/F2 6.545454545454544 Tf +(100k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +500.400 565.200 m +514.800 565.200 l +S +500.400 565.200 m +500.400 579.600 l +S +500.400 579.600 m +500.400 583.200 l +S +550.800 579.600 m +500.400 579.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +500.400 565.200 m +514.800 565.200 l +S +500.400 565.200 m +500.400 579.600 l +S +500.400 579.600 m +500.400 583.200 l +S +550.800 579.600 m +500.400 579.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +481.67 616.91 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +500.400 612.000 m +500.400 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +481.67 616.91 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +500.400 612.000 m +500.400 615.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +579.600 579.600 m +572.400 579.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +550.800 579.600 m +558.000 579.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +558.00 582.48 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +558.00 584.51 Td +(R16) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +558.00 570.11 Td +/F2 6.545454545454544 Tf +(100k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +558.000 558.000 m +586.800 558.000 l +S +586.800 579.600 m +586.800 558.000 l +S +579.600 579.600 m +586.800 579.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +558.000 558.000 m +586.800 558.000 l +S +586.800 579.600 m +586.800 558.000 l +S +579.600 579.600 m +586.800 579.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +586.800 558.000 m +586.800 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 550.800 m +594.000 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.080 544.320 m +587.520 544.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +583.920 546.480 m +589.680 546.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +581.760 548.640 m +591.840 548.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +579.53 537.71 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +533.26 526.91 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +558.000 532.800 m +558.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +533.26 526.91 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +558.000 532.800 m +558.000 550.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +474.94 559.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +514.800 558.000 m +500.400 558.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +474.94 559.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +514.800 558.000 m +500.400 558.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +500.400 529.200 m +500.400 536.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +500.400 558.000 m +500.400 550.800 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +497.52 550.80 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +482.40 544.91 Td +(R17) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +475.20 537.71 Td +/F2 6.545454545454544 Tf +(100k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +514.800 550.800 m +514.800 529.200 l +S +514.800 529.200 m +500.400 529.200 l +S +500.400 529.200 m +500.400 518.400 l +S +500.400 518.400 m +572.400 518.400 l +S +572.400 518.400 m +572.400 565.200 l +S +572.400 565.200 m +558.000 565.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +514.800 550.800 m +514.800 529.200 l +S +514.800 529.200 m +500.400 529.200 l +S +500.400 529.200 m +500.400 518.400 l +S +500.400 518.400 m +572.400 518.400 l +S +572.400 518.400 m +572.400 565.200 l +S +572.400 565.200 m +558.000 565.200 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +450.00 633.60 169.20 -133.20 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 130.45 443.44 Tm +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 127.57 459.42 Tm +(25) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +129.600 468.000 m +129.600 460.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +142.13 450.65 Td +(PWREN#) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 454.25 Td +(24) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 453.600 m +172.800 453.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 456.480 m +182.880 450.720 l +177.120 450.720 m +182.880 456.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +153.77 443.45 Td +(LED2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 447.05 Td +(23) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 446.400 m +172.800 446.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 449.280 m +182.880 443.520 l +177.120 443.520 m +182.880 449.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +153.77 436.25 Td +(LED1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 439.85 Td +(22) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 439.200 m +172.800 439.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 442.080 m +182.880 436.320 l +177.120 436.320 m +182.880 442.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +138.49 429.05 Td +(LED4/SDA) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 432.65 Td +(21) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 432.000 m +172.800 432.000 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 434.880 m +182.880 429.120 l +177.120 429.120 m +182.880 434.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +149.04 421.85 Td +(VDD33) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 425.45 Td +(20) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 424.800 m +172.800 424.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +162.13 414.65 Td +(V5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 418.25 Td +(19) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 417.600 m +172.800 417.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +149.40 407.45 Td +(PSELF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 411.05 Td +(18) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 410.400 m +172.800 410.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 413.280 m +182.880 407.520 l +177.120 407.520 m +182.880 413.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +160.68 400.25 Td +(NC) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 403.85 Td +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 403.200 m +172.800 403.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 406.080 m +182.880 400.320 l +177.120 400.320 m +182.880 406.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +129.04 393.05 Td +(RESET#/CDP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 396.65 Td +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 396.000 m +172.800 396.000 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 398.880 m +182.880 393.120 l +177.120 393.120 m +182.880 398.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +156.32 385.85 Td +(DPU) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 389.45 Td +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 388.800 m +172.800 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +155.23 378.65 Td +(DMU) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 382.25 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 381.600 m +172.800 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +139.22 371.45 Td +(LED3/SCL) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +173.16 375.05 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +180.000 374.400 m +172.800 374.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +177.120 377.280 m +182.880 371.520 l +177.120 371.520 m +182.880 377.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 371.45 Td +(DP1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +78.76 375.05 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 374.400 m +86.400 374.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 378.65 Td +(DM1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +78.76 382.25 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 381.600 m +86.400 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 385.85 Td +(DP2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +78.76 389.45 Td +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 388.800 m +86.400 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 393.05 Td +(DM2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 396.65 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 396.000 m +86.400 396.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 400.25 Td +(DP3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 403.85 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 403.200 m +86.400 403.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 406.080 m +82.080 400.320 l +76.320 400.320 m +82.080 406.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 407.45 Td +(DM3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 411.05 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 410.400 m +86.400 410.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 413.280 m +82.080 407.520 l +76.320 407.520 m +82.080 413.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 414.65 Td +(DP4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 418.25 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 417.600 m +86.400 417.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 420.480 m +82.080 414.720 l +76.320 414.720 m +82.080 420.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 421.85 Td +(DM4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 425.45 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 424.800 m +86.400 424.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 427.680 m +82.080 421.920 l +76.320 421.920 m +82.080 427.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 429.05 Td +(XI) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 432.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 432.000 m +86.400 432.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 436.25 Td +(XO) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 439.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 439.200 m +86.400 439.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 443.45 Td +(NC.) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 447.05 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 446.400 m +86.400 446.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 449.280 m +82.080 443.520 l +76.320 443.520 m +82.080 449.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +89.06 450.65 Td +(OVCUR#) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +82.40 454.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 453.600 m +86.400 453.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +76.320 456.480 m +82.080 450.720 l +76.320 450.720 m +82.080 456.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +91.08 457.20 m 91.08 457.80 90.60 458.28 90.00 458.28 c +89.40 458.28 88.92 457.80 88.92 457.20 c +88.92 456.60 89.40 456.12 90.00 456.12 c +90.60 456.12 91.08 456.60 91.08 457.20 c +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.40 460.80 86.40 -93.60 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +86.40 361.31 Td +(U11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +144.00 465.71 Td +(CH334F) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +185.27 390.11 Td +(D_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +198.000 388.800 m +180.000 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +185.27 390.11 Td +(D_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +198.000 388.800 m +180.000 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +184.91 382.91 Td +(D_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +180.000 381.600 m +198.000 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +184.91 382.91 Td +(D_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +180.000 381.600 m +198.000 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 375.71 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 374.400 m +50.400 374.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 375.71 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 374.400 m +50.400 374.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 382.91 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 381.600 m +50.400 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 382.91 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 381.600 m +50.400 381.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 390.11 Td +(USB2_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 388.800 m +50.400 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 390.11 Td +(USB2_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 388.800 m +50.400 388.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 397.31 Td +(USB2_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 396.000 m +50.400 396.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 397.31 Td +(USB2_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 396.000 m +50.400 396.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +64.80 433.31 Td +(XI) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 432.000 m +64.800 432.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +64.80 433.31 Td +(XI) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 432.000 m +64.800 432.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +64.80 440.51 Td +(XO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 439.200 m +64.800 439.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +64.80 440.51 Td +(XO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 439.200 m +64.800 439.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +210.240 435.600 m +216.000 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +194.400 435.600 m +201.600 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +207.360 429.840 m +207.360 441.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +201.600 435.600 m +207.360 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +223.200 435.600 m +216.000 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +210.240 441.360 m +210.240 429.840 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +212.40 429.28 Td +(C16) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +212.40 436.91 Td +(1uF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +194.40 451.31 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +194.400 435.600 m +194.400 424.800 l +S +194.400 424.800 m +180.000 424.800 l +S +194.400 417.600 m +194.400 424.800 l +S +180.000 417.600 m +194.400 417.600 l +S +194.400 435.600 m +194.400 450.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +194.40 451.31 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +194.400 435.600 m +194.400 424.800 l +S +194.400 424.800 m +180.000 424.800 l +S +194.400 417.600 m +194.400 424.800 l +S +180.000 417.600 m +194.400 417.600 l +S +194.400 435.600 m +194.400 450.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +210.240 417.600 m +216.000 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +194.400 417.600 m +201.600 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +207.360 411.840 m +207.360 423.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +201.600 417.600 m +207.360 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +223.200 417.600 m +216.000 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +210.240 423.360 m +210.240 411.840 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +212.40 407.68 Td +(C17) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +212.40 411.71 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +223.200 417.600 m +223.200 428.400 l +S +223.200 435.600 m +223.200 428.400 l +S +223.200 428.400 m +234.000 428.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +223.200 417.600 m +223.200 428.400 l +S +223.200 435.600 m +223.200 428.400 l +S +223.200 428.400 m +234.000 428.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +234.000 428.400 m +234.000 421.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +226.800 421.200 m +241.200 421.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +233.280 414.720 m +234.720 414.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +231.120 416.880 m +236.880 416.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +228.960 419.040 m +239.040 419.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +226.73 408.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +129.600 468.000 m +129.600 475.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +136.800 475.200 m +122.400 475.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +130.320 481.680 m +128.880 481.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +132.480 479.520 m +126.720 479.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +134.640 477.360 m +124.560 477.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +122.33 483.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +129.600 468.000 m +129.600 468.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +129.600 468.000 m +129.600 468.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 301.75 400.28 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +302.400 399.600 m +302.400 406.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 287.35 438.48 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +288.000 442.800 m +288.000 435.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 287.35 400.28 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +288.000 399.600 m +288.000 406.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 301.75 438.48 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +302.400 442.800 m +302.400 435.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +280.80 435.60 28.80 -28.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +307.08 410.40 m 307.08 411.00 306.60 411.48 306.00 411.48 c +305.40 411.48 304.92 411.00 304.92 410.40 c +304.92 409.80 305.40 409.32 306.00 409.32 c +306.60 409.32 307.08 409.80 307.08 410.40 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +300.240 417.600 m +290.160 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +300.240 424.800 m +290.160 424.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +302.400 406.800 m +302.400 414.000 l +295.200 414.000 l +295.200 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +288.000 435.600 m +288.000 428.400 l +295.200 428.400 l +295.200 424.800 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +290.16 422.64 10.08 -2.88 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +309.60 429.71 Td +(U12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +309.60 418.91 Td +(12MHz) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +288.000 399.600 m +284.400 399.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +288.000 399.600 m +284.400 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +334.800 442.800 m +342.000 442.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +342.000 435.600 m +342.000 450.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +348.480 442.080 m +348.480 443.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +346.320 439.920 m +346.320 445.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +344.160 437.760 m +344.160 447.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 355.09 435.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +302.400 442.800 m +331.200 442.800 l +S +331.200 442.800 m +331.200 453.600 l +S +331.200 453.600 m +309.600 453.600 l +S +331.200 442.800 m +331.200 399.600 l +S +331.200 399.600 m +324.000 399.600 l +S +331.200 442.800 m +334.800 442.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +302.400 442.800 m +331.200 442.800 l +S +331.200 442.800 m +331.200 453.600 l +S +331.200 453.600 m +309.600 453.600 l +S +331.200 442.800 m +331.200 399.600 l +S +331.200 399.600 m +324.000 399.600 l +S +331.200 442.800 m +334.800 442.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 399.600 m +277.200 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +277.200 406.800 m +277.200 392.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +270.720 400.320 m +270.720 398.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +272.880 402.480 m +272.880 396.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +275.040 404.640 m +275.040 394.560 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 268.69 392.33 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +311.760 405.360 m +311.760 393.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +314.640 405.360 m +314.640 393.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +302.400 399.600 m +309.600 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +324.000 399.600 m +316.800 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +309.600 399.600 m +311.760 399.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +314.640 399.600 m +316.800 399.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +316.80 393.71 Td +(C18) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +309.60 386.51 Td +(15pF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +245.81 386.51 Td +(XI) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +302.400 399.600 m +302.400 385.200 l +S +259.200 385.200 m +302.400 385.200 l +S +259.200 410.400 m +259.200 385.200 l +S +252.000 385.200 m +259.200 385.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +245.81 386.51 Td +(XI) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +302.400 399.600 m +302.400 385.200 l +S +259.200 385.200 m +302.400 385.200 l +S +259.200 410.400 m +259.200 385.200 l +S +252.000 385.200 m +259.200 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +297.360 459.360 m +297.360 447.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +300.240 459.360 m +300.240 447.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +288.000 453.600 m +295.200 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +309.600 453.600 m +302.400 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +295.200 453.600 m +297.360 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +300.240 453.600 m +302.400 453.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +295.20 462.11 Td +(C19) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +302.40 454.91 Td +(15pF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +288.000 442.800 m +288.000 453.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +288.000 442.800 m +288.000 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +259.200 453.600 m +266.400 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +288.000 453.600 m +280.800 453.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +266.40 456.48 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +266.40 458.51 Td +(R18) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +266.40 444.11 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +242.54 447.71 Td +(XO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +259.200 439.200 m +259.200 453.600 l +S +252.000 453.600 m +259.200 453.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +242.54 447.71 Td +(XO) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +259.200 439.200 m +259.200 453.600 l +S +252.000 453.600 m +259.200 453.600 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +216.00 369.82 Td +(Hub) Tj +ET +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +39.60 493.20 324.00 -136.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +545.040 409.680 m +546.480 412.560 l +547.920 411.120 l +545.040 409.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +542.160 412.560 m +543.600 415.440 l +545.040 414.000 l +542.160 412.560 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +550.080 414.720 m +547.200 411.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +547.200 417.600 m +544.320 414.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +554.400 417.600 m +554.400 414.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +554.400 428.400 m +554.400 424.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +549.360 417.600 m +559.440 417.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +549.360 424.800 m +554.400 417.600 l +559.440 424.800 l +549.360 424.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +554.400 406.800 m +554.400 414.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +554.400 435.600 m +554.400 428.400 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +561.60 422.08 Td +(LED3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +554.400 460.800 m +554.400 453.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +554.400 432.000 m +554.400 439.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +551.52 453.60 5.76 -14.40 re +S +7.20 w +BT +/F2 9.818181818181817 Tf +10.80 TL +0.000 0.000 0.502 rg +561.60 444.76 Td +(R21) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +561.60 436.91 Td +/F2 6.545454545454544 Tf +(10k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +561.60 462.11 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 460.800 m +554.400 468.000 l +S +554.400 468.000 m +561.600 468.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +561.60 462.11 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 460.800 m +554.400 468.000 l +S +554.400 468.000 m +561.600 468.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 432.000 m +554.400 435.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 432.000 m +554.400 435.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +568.800 406.800 m +576.000 406.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +576.000 399.600 m +576.000 414.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +582.480 406.080 m +582.480 407.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +580.320 403.920 m +580.320 409.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +578.160 401.760 m +578.160 411.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 589.09 399.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 406.800 m +568.800 406.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +554.400 406.800 m +568.800 406.800 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +514.80 493.20 100.80 -136.80 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +554.40 377.02 Td +(LEDs) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +140.40 309.60 64.80 -64.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +145.08 306.00 m 145.08 306.60 144.60 307.08 144.00 307.08 c +143.40 307.08 142.92 306.60 142.92 306.00 c +142.92 305.40 143.40 304.92 144.00 304.92 c +144.60 304.92 145.08 305.40 145.08 306.00 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 299.45 Td +(VIO) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 303.05 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 302.400 m +140.400 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 292.25 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 295.85 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 295.200 m +140.400 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 285.05 Td +(VDD5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 288.65 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 288.000 m +140.400 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 277.85 Td +(TXD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 281.45 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 280.800 m +140.400 280.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 270.65 Td +(RXD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 274.25 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 273.600 m +140.400 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 263.45 Td +(V3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 267.05 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 266.400 m +140.400 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 256.25 Td +(UD+) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 259.85 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 259.200 m +140.400 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +143.06 249.05 Td +(UD-) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +136.40 252.65 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +133.200 252.000 m +140.400 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +184.71 249.05 Td +(VBUS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 252.65 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 252.000 m +205.200 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +185.81 256.25 Td +(ACT#) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 259.85 Td +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 259.200 m +205.200 259.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +209.520 262.080 m +215.280 256.320 l +209.520 256.320 m +215.280 262.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +188.36 263.45 Td +(DCD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 267.05 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 266.400 m +205.200 266.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +209.520 269.280 m +215.280 263.520 l +209.520 263.520 m +215.280 269.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +169.09 270.65 Td +(DTRTNOW) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 274.25 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 273.600 m +205.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +189.45 277.85 Td +(RTS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 281.45 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 280.800 m +205.200 280.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +188.72 285.05 Td +(DSR) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 288.65 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 288.000 m +205.200 288.000 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +209.520 290.880 m +215.280 285.120 l +209.520 285.120 m +215.280 290.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +189.45 292.25 Td +(CTS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 295.85 Td +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 295.200 m +205.200 295.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +209.520 298.080 m +215.280 292.320 l +209.520 292.320 m +215.280 298.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +195.99 299.45 Td +(RI) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +205.56 303.05 Td +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +212.400 302.400 m +205.200 302.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +209.520 305.280 m +215.280 299.520 l +209.520 299.520 m +215.280 305.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 173.65 298.05 Tm +(EP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 170.77 308.22 Tm +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +172.800 316.800 m +172.800 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +144.00 310.91 Td +(U14) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +183.60 314.51 Td +(CH343P) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +90.000 295.200 m +90.000 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +97.200 302.400 m +82.800 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +90.720 308.880 m +89.280 308.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +92.880 306.720 m +87.120 306.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +95.040 304.560 m +84.960 304.560 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +82.73 310.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +90.000 295.200 m +133.200 295.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +90.000 295.200 m +133.200 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +219.600 223.200 m +219.600 216.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +212.400 216.000 m +226.800 216.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +218.880 209.520 m +220.320 209.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +216.720 211.680 m +222.480 211.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +214.560 213.840 m +224.640 213.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +212.33 202.91 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 260.51 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 252.000 m +212.400 252.000 l +S +219.600 252.000 m +219.600 259.200 l +S +219.600 248.400 m +219.600 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 260.51 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 252.000 m +212.400 252.000 l +S +219.600 252.000 m +219.600 259.200 l +S +219.600 248.400 m +219.600 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 274.91 Td +(DTR) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 273.600 m +212.400 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 274.91 Td +(DTR) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 273.600 m +212.400 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 282.11 Td +(RTS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 280.800 m +212.400 280.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 282.11 Td +(RTS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 280.800 m +212.400 280.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +115.200 314.640 m +115.200 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +115.200 309.600 m +115.200 311.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +115.200 324.000 m +115.200 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +115.200 302.400 m +115.200 309.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +109.440 314.640 m +120.960 314.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +109.440 311.760 m +120.960 311.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +97.20 325.31 Td +(C22) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.60 318.11 Td +(100nF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +129.60 321.71 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +129.600 302.400 m +133.200 302.400 l +S +129.600 320.400 m +129.600 302.400 l +S +129.600 302.400 m +115.200 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +129.60 321.71 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +129.600 302.400 m +133.200 302.400 l +S +129.600 320.400 m +129.600 302.400 l +S +129.600 302.400 m +115.200 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +115.200 324.000 m +115.200 331.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +122.400 331.200 m +108.000 331.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +115.920 337.680 m +114.480 337.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +118.080 335.520 m +112.320 335.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +120.240 333.360 m +110.160 333.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +107.93 339.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 324.000 m +115.200 324.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 324.000 m +115.200 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +79.200 275.040 m +79.200 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +79.200 270.000 m +79.200 272.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 284.400 m +79.200 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 262.800 m +79.200 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +73.440 275.040 m +84.960 275.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +73.440 272.160 m +84.960 272.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +82.80 264.11 Td +(C23) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +82.80 278.51 Td +(100nF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +47.26 282.11 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 288.000 m +133.200 288.000 l +S +79.200 284.400 m +79.200 288.000 l +S +79.200 288.000 m +72.000 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +47.26 282.11 Td +(3V3_OP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 288.000 m +133.200 288.000 l +S +79.200 284.400 m +79.200 288.000 l +S +79.200 288.000 m +72.000 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +79.200 259.200 m +72.000 259.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +72.000 266.400 m +72.000 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +65.520 259.920 m +65.520 258.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +67.680 262.080 m +67.680 256.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +69.840 264.240 m +69.840 254.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 63.49 251.93 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 259.200 m +79.200 262.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +79.200 259.200 m +79.200 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +100.800 277.200 m +100.800 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +100.800 248.400 m +100.800 255.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +97.92 270.00 5.76 -14.40 re +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +90.00 249.28 Td +(R22) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +90.00 253.31 Td +/F2 6.545454545454544 Tf +(0) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +111.600 270.000 m +111.600 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +111.600 241.200 m +111.600 248.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +108.72 262.80 5.76 -14.40 re +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +100.80 238.48 Td +(R23) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +100.80 242.51 Td +/F2 6.545454545454544 Tf +(0) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 280.800 m +100.800 280.800 l +S +100.800 277.200 m +100.800 280.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 280.800 m +100.800 280.800 l +S +100.800 277.200 m +100.800 280.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +111.600 273.600 m +111.600 270.000 l +S +111.600 273.600 m +133.200 273.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +111.600 273.600 m +111.600 270.000 l +S +111.600 273.600 m +133.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +69.63 238.91 Td +(EIORX) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +90.000 244.800 m +100.800 244.800 l +S +100.800 248.400 m +100.800 244.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +69.63 238.91 Td +(EIORX) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +90.000 244.800 m +100.800 244.800 l +S +100.800 248.400 m +100.800 244.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +81.16 228.11 Td +(EIOTX) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +100.800 234.000 m +111.600 234.000 l +S +111.600 234.000 m +111.600 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +81.16 228.11 Td +(EIOTX) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +100.800 234.000 m +111.600 234.000 l +S +111.600 234.000 m +111.600 241.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +118.800 228.240 m +118.800 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +118.800 223.200 m +118.800 225.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +118.800 237.600 m +118.800 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +118.800 216.000 m +118.800 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +113.040 228.240 m +124.560 228.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +113.040 225.360 m +124.560 225.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +104.40 210.11 Td +(C24) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +97.20 217.31 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 266.400 m +118.800 266.400 l +S +118.800 266.400 m +118.800 237.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 266.400 m +118.800 266.400 l +S +118.800 266.400 m +118.800 237.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +118.800 216.000 m +118.800 208.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +111.600 208.800 m +126.000 208.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +118.080 202.320 m +119.520 202.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +115.920 204.480 m +121.680 204.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +113.760 206.640 m +123.840 206.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +111.53 195.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 216.000 m +118.800 216.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 216.000 m +118.800 216.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +126.00 231.71 Td +(USB2_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +126.000 237.600 m +126.000 259.200 l +S +126.000 259.200 m +133.200 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +126.00 231.71 Td +(USB2_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +126.000 237.600 m +126.000 259.200 l +S +126.000 259.200 m +133.200 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +158.40 235.31 Td +(USB2_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 241.200 m +158.400 241.200 l +S +133.200 241.200 m +133.200 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +158.40 235.31 Td +(USB2_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +133.200 241.200 m +158.400 241.200 l +S +133.200 241.200 m +133.200 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +172.800 316.800 m +172.800 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +180.000 324.000 m +165.600 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +173.520 330.480 m +172.080 330.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +175.680 328.320 m +169.920 328.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +177.840 326.160 m +167.760 326.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +165.53 332.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +172.800 316.800 m +172.800 316.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +172.800 316.800 m +172.800 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +306.000 237.600 m +306.000 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +320.400 252.000 m +313.200 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +306.000 266.400 m +306.000 259.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +306.000 244.800 m +313.200 249.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 254.160 m +306.000 259.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 245.520 m +313.200 258.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +306.000 259.200 m +308.160 255.600 l +310.320 258.480 l +306.000 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +316.80 256.91 Td +(Q2) Tj +ET +7.20 w +BT +/F2 5.236363636363636 Tf +5.76 TL +0.000 0.000 1.000 rg +309.60 238.65 Td +(S8050) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +306.000 302.400 m +306.000 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +320.400 288.000 m +313.200 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +306.000 273.600 m +306.000 280.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +306.000 295.200 m +313.200 290.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 285.840 m +306.000 280.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 294.480 m +313.200 281.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +306.000 280.800 m +308.160 284.400 l +310.320 281.520 l +306.000 280.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +316.80 292.91 Td +(Q3) Tj +ET +7.20 w +BT +/F2 5.236363636363636 Tf +5.76 TL +0.000 0.000 1.000 rg +309.60 274.65 Td +(S8050) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +349.200 288.000 m +342.000 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +320.400 288.000 m +327.600 288.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.60 290.88 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +327.60 292.91 Td +(R24) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +327.60 278.51 Td +/F2 6.545454545454544 Tf +(12k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +320.400 288.000 m +320.400 288.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +320.400 288.000 m +320.400 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +349.200 252.000 m +342.000 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +320.400 252.000 m +327.600 252.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.60 254.88 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +327.60 256.91 Td +(R25) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +327.60 242.51 Td +/F2 6.545454545454544 Tf +(12k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +320.400 252.000 m +320.400 252.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +320.400 252.000 m +320.400 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +356.40 282.11 Td +(DTR) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +352.800 288.000 m +349.200 288.000 l +S +352.800 266.400 m +352.800 288.000 l +S +352.800 266.400 m +306.000 266.400 l +S +356.400 288.000 m +352.800 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +356.40 282.11 Td +(DTR) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +352.800 288.000 m +349.200 288.000 l +S +352.800 266.400 m +352.800 288.000 l +S +352.800 266.400 m +306.000 266.400 l +S +356.400 288.000 m +352.800 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +356.40 253.31 Td +(RTS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 252.000 m +349.200 252.000 l +S +349.200 252.000 m +349.200 273.600 l +S +306.000 273.600 m +349.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +356.40 253.31 Td +(RTS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +356.400 252.000 m +349.200 252.000 l +S +349.200 252.000 m +349.200 273.600 l +S +306.000 273.600 m +349.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +295.20 310.91 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 298.800 m +284.400 306.000 l +S +295.200 306.000 m +284.400 306.000 l +S +295.200 309.600 m +295.200 306.000 l +S +295.200 306.000 m +306.000 306.000 l +S +306.000 306.000 m +306.000 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +295.20 310.91 Td +(#EN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 298.800 m +284.400 306.000 l +S +295.200 306.000 m +284.400 306.000 l +S +295.200 309.600 m +295.200 306.000 l +S +295.200 306.000 m +306.000 306.000 l +S +306.000 306.000 m +306.000 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +295.20 228.11 Td +(EIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 237.600 m +284.400 241.200 l +S +295.200 237.600 m +284.400 237.600 l +S +295.200 234.000 m +295.200 237.600 l +S +295.200 237.600 m +306.000 237.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +295.20 228.11 Td +(EIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 237.600 m +284.400 241.200 l +S +295.200 237.600 m +284.400 237.600 l +S +295.200 234.000 m +295.200 237.600 l +S +295.200 237.600 m +306.000 237.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +290.160 282.960 m +278.640 282.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 270.000 m +284.400 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +284.400 291.600 m +284.400 285.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +278.640 285.840 m +290.160 285.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 298.800 m +284.400 291.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +284.400 282.960 m +284.400 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +288.00 289.31 Td +(C25) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +266.40 289.31 Td +(4.7uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +284.400 257.040 m +284.400 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 241.200 m +284.400 248.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +290.160 254.160 m +278.640 254.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +284.400 248.400 m +284.400 254.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 270.000 m +284.400 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +278.640 257.040 m +290.160 257.040 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +288.00 249.28 Td +(C26) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +270.00 246.11 Td +(1uF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 270.000 m +284.400 270.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +284.400 270.000 m +284.400 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +284.400 270.000 m +277.200 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +277.200 277.200 m +277.200 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +270.720 270.720 m +270.720 269.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +272.880 272.880 m +272.880 267.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +275.040 275.040 m +275.040 264.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 268.69 262.73 Tm +(GND) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +439.20 316.80 36.00 -93.60 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 306.65 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +419.19 310.25 Td +(A1B12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 309.600 m +439.200 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 299.45 Td +(VBUS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +422.83 303.05 Td +(A4B9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 302.400 m +439.200 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 292.25 Td +(SBU2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 295.85 Td +(B8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 295.200 m +439.200 295.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +429.120 298.080 m +434.880 292.320 l +429.120 292.320 m +434.880 298.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 285.05 Td +(CC1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 288.65 Td +(A5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 288.000 m +439.200 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 277.85 Td +(DN2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 281.45 Td +(B7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 280.800 m +439.200 280.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 270.65 Td +(DP1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 274.25 Td +(A6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 273.600 m +439.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 263.45 Td +(DN1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 267.05 Td +(A7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 266.400 m +439.200 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 256.25 Td +(DP2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 259.85 Td +(B6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 259.200 m +439.200 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 249.05 Td +(SBU1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 252.65 Td +(A8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 252.000 m +439.200 252.000 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +429.120 254.880 m +434.880 249.120 l +429.120 249.120 m +434.880 254.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 241.85 Td +(CC2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +430.83 245.45 Td +(B5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 244.800 m +439.200 244.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 234.65 Td +(VBUS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +422.83 238.25 Td +(B4A9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 237.600 m +439.200 237.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +441.86 227.45 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +419.19 231.05 Td +(B1A12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +432.000 230.400 m +439.200 230.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +464.67 249.77 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +475.20 252.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 252.000 m +475.200 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +464.67 242.57 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +475.20 245.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 244.800 m +475.200 244.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +464.67 235.37 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +475.20 238.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 237.600 m +475.200 237.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +464.67 228.17 Td +(EH) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +475.20 231.05 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 230.400 m +475.200 230.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +439.20 318.11 Td +(ESPUSB) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +439.20 217.31 Td +(TYPE-C-31-M-12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 309.600 m +417.600 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +424.800 316.800 m +410.400 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +418.320 323.280 m +416.880 323.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +420.480 321.120 m +414.720 321.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +422.640 318.960 m +412.560 318.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +410.33 325.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 309.600 m +417.600 309.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 309.600 m +417.600 309.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 230.400 m +417.600 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +410.400 223.200 m +424.800 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +416.880 216.720 m +418.320 216.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.720 218.880 m +420.480 218.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +412.560 221.040 m +422.640 221.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +410.33 210.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 230.400 m +417.600 230.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 230.400 m +417.600 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 230.400 m +489.600 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 223.200 m +489.600 237.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +496.080 229.680 m +496.080 231.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +493.920 227.520 m +493.920 233.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +491.760 225.360 m +491.760 235.440 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 230.400 m +482.400 230.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 230.400 m +482.400 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 237.600 m +489.600 237.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 230.400 m +489.600 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +496.080 236.880 m +496.080 238.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +493.920 234.720 m +493.920 240.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +491.760 232.560 m +491.760 242.640 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 237.600 m +482.400 237.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 237.600 m +482.400 237.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 244.800 m +489.600 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 237.600 m +489.600 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +496.080 244.080 m +496.080 245.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +493.920 241.920 m +493.920 247.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +491.760 239.760 m +491.760 249.840 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 244.800 m +482.400 244.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 244.800 m +482.400 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 252.000 m +489.600 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 244.800 m +489.600 259.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +496.080 251.280 m +496.080 252.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +493.920 249.120 m +493.920 254.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +491.760 246.960 m +491.760 257.040 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 252.000 m +482.400 252.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 252.000 m +482.400 252.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +403.20 267.71 Td +(D_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 273.600 m +417.600 273.600 l +S +417.600 273.600 m +417.600 259.200 l +S +417.600 259.200 m +432.000 259.200 l +S +417.600 273.600 m +403.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +403.20 267.71 Td +(D_P) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 273.600 m +417.600 273.600 l +S +417.600 273.600 m +417.600 259.200 l +S +417.600 259.200 m +432.000 259.200 l +S +417.600 273.600 m +403.200 273.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +403.20 260.51 Td +(D_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 266.400 m +424.800 266.400 l +S +424.800 266.400 m +424.800 280.800 l +S +424.800 280.800 m +432.000 280.800 l +S +424.800 266.400 m +403.200 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +403.20 260.51 Td +(D_N) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 266.400 m +424.800 266.400 l +S +424.800 266.400 m +424.800 280.800 l +S +424.800 280.800 m +432.000 280.800 l +S +424.800 266.400 m +403.200 266.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +424.800 302.400 m +414.000 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +396.000 302.400 m +406.800 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +404.640 306.720 m +404.640 307.440 l +406.080 307.440 l +406.080 296.640 l +407.520 296.640 l +407.520 297.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.000 306.720 m +406.800 302.400 l +414.000 297.360 l +414.000 306.720 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +396.00 303.71 Td +(D3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +385.20 310.91 Td +(B5819WS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 302.400 m +424.800 302.400 l +S +424.800 295.200 m +424.800 302.400 l +S +374.400 295.200 m +424.800 295.200 l +S +374.400 216.000 m +374.400 295.200 l +S +406.800 216.000 m +374.400 216.000 l +S +406.800 237.600 m +406.800 216.000 l +S +432.000 237.600 m +406.800 237.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 302.400 m +424.800 302.400 l +S +424.800 295.200 m +424.800 302.400 l +S +374.400 295.200 m +424.800 295.200 l +S +374.400 216.000 m +374.400 295.200 l +S +406.800 216.000 m +374.400 216.000 l +S +406.800 237.600 m +406.800 216.000 l +S +432.000 237.600 m +406.800 237.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +370.80 318.11 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +370.800 302.400 m +370.800 316.800 l +S +370.800 302.400 m +396.000 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +370.80 318.11 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +370.800 302.400 m +370.800 316.800 l +S +370.800 302.400 m +396.000 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 288.000 m +406.800 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +385.200 288.000 m +392.400 288.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +392.40 290.88 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +392.40 292.91 Td +(R26) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +392.40 278.51 Td +/F2 6.545454545454544 Tf +(5.1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 288.000 m +414.000 288.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 288.000 m +414.000 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +385.200 284.400 m +385.200 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +378.000 277.200 m +392.400 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +384.480 270.720 m +385.920 270.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +382.320 272.880 m +388.080 272.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +380.160 275.040 m +390.240 275.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +377.93 264.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +385.200 288.000 m +385.200 284.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +385.200 288.000 m +385.200 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +421.200 244.800 m +414.000 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +392.400 244.800 m +399.600 244.800 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +399.60 247.68 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +399.60 249.71 Td +(R27) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +399.60 235.31 Td +/F2 6.545454545454544 Tf +(5.1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +392.400 241.200 m +392.400 244.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +392.400 241.200 m +392.400 244.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +392.400 241.200 m +392.400 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +385.200 234.000 m +399.600 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +391.680 227.520 m +393.120 227.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +389.520 229.680 m +395.280 229.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +387.360 231.840 m +397.440 231.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +385.13 220.91 Td +(GND) Tj +ET +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +255.60 200.62 Td +(USB to UART) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.00 486.00 64.80 -25.20 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +418.68 482.40 m 418.68 483.00 418.20 483.48 417.60 483.48 c +417.00 483.48 416.52 483.00 416.52 482.40 c +416.52 481.80 417.00 481.32 417.60 481.32 c +418.20 481.32 418.68 481.80 418.68 482.40 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +416.66 475.85 Td +(ADJ\(GND\)) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +410.00 479.45 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +406.800 478.800 m +414.000 478.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +416.66 468.65 Td +(VOUT\(TAB\)) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +410.00 472.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +406.800 471.600 m +414.000 471.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +416.66 461.45 Td +(VIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +410.00 465.05 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +406.800 464.400 m +414.000 464.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +463.41 468.65 Td +(TAB) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +479.16 472.25 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +486.000 471.600 m +478.800 471.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +483.120 474.480 m +488.880 468.720 l +483.120 468.720 m +488.880 474.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +414.00 487.31 Td +(U15) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +414.00 454.91 Td +(AMS1117-3.3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +435.600 426.240 m +435.600 428.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +435.600 421.200 m +435.600 423.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +435.600 435.600 m +435.600 428.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +435.600 414.000 m +435.600 421.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +429.840 426.240 m +441.360 426.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +429.840 423.360 m +441.360 423.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +439.20 415.31 Td +(C27) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +439.20 429.71 Td +(100nF) Tj +ET +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +39.60 349.20 468.00 -158.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +435.60 440.51 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +435.600 435.600 m +435.600 439.200 l +S +435.600 439.200 m +414.000 439.200 l +S +414.000 439.200 m +406.800 439.200 l +S +406.800 439.200 m +406.800 464.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +435.60 440.51 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +435.600 435.600 m +435.600 439.200 l +S +435.600 439.200 m +414.000 439.200 l +S +414.000 439.200 m +406.800 439.200 l +S +406.800 439.200 m +406.800 464.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +435.60 397.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +399.600 396.000 m +399.600 471.600 l +S +399.600 471.600 m +406.800 471.600 l +S +399.600 396.000 m +414.000 396.000 l +S +414.000 396.000 m +435.600 396.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +435.60 397.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +399.600 396.000 m +399.600 471.600 l +S +399.600 471.600 m +406.800 471.600 l +S +399.600 396.000 m +414.000 396.000 l +S +414.000 396.000 m +435.600 396.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +414.000 417.600 m +414.000 414.000 l +S +414.000 414.000 m +435.600 414.000 l +S +478.800 414.000 m +435.600 414.000 l +S +478.800 414.000 m +478.800 385.200 l +S +478.800 374.400 m +478.800 385.200 l +S +478.800 374.400 m +435.600 374.400 l +S +414.000 374.400 m +435.600 374.400 l +S +392.400 374.400 m +414.000 374.400 l +S +392.400 478.800 m +392.400 374.400 l +S +392.400 478.800 m +406.800 478.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +414.000 417.600 m +414.000 414.000 l +S +414.000 414.000 m +435.600 414.000 l +S +478.800 414.000 m +435.600 414.000 l +S +478.800 414.000 m +478.800 385.200 l +S +478.800 374.400 m +478.800 385.200 l +S +478.800 374.400 m +435.600 374.400 l +S +414.000 374.400 m +435.600 374.400 l +S +392.400 374.400 m +414.000 374.400 l +S +392.400 478.800 m +392.400 374.400 l +S +392.400 478.800 m +406.800 478.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +435.600 386.640 m +435.600 388.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +435.600 381.600 m +435.600 383.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +435.600 396.000 m +435.600 388.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +435.600 374.400 m +435.600 381.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +429.840 386.640 m +441.360 386.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +429.840 383.760 m +441.360 383.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +439.20 375.71 Td +(C30) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +439.20 390.11 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +478.800 385.200 m +471.600 385.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +471.600 392.400 m +471.600 378.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +465.120 385.920 m +465.120 384.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +467.280 388.080 m +467.280 382.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +469.440 390.240 m +469.440 380.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 463.09 377.93 Tm +(GND) Tj +ET +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +514.80 349.20 104.40 -158.40 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +421.20 359.02 Td +(Power) Tj +ET +2 J +0 j +72 M +1.44 w +0.00 G +[] 0 d +28.80 788.40 597.60 -604.80 re +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 572.400 m +1162.800 572.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 572.400 m +1162.800 572.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1148.400 543.600 m +1162.800 543.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1148.400 543.600 m +1162.800 543.600 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +993.60 781.20 194.40 -136.80 re +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +993.60 637.20 194.40 -108.00 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 426.960 m +419.760 426.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 429.840 m +419.760 429.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 417.600 m +414.000 424.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 439.200 m +414.000 432.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.000 424.800 m +414.000 426.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.000 429.840 m +414.000 432.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +417.60 429.28 Td +(C32) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +403.20 415.31 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 383.760 m +419.760 383.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 386.640 m +419.760 386.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 374.400 m +414.000 381.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 396.000 m +414.000 388.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.000 381.600 m +414.000 383.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +414.000 386.640 m +414.000 388.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +417.60 378.88 Td +(C33) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +414.00 390.11 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +213.840 236.160 m +225.360 236.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +213.840 239.040 m +225.360 239.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +219.600 226.800 m +219.600 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +219.600 248.400 m +219.600 241.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +219.600 234.000 m +219.600 236.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +219.600 239.040 m +219.600 241.200 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +223.20 231.28 Td +(C34) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +219.60 242.51 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 226.800 m +219.600 223.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +219.600 226.800 m +219.600 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.200 673.200 m +565.200 666.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +558.000 666.000 m +572.400 666.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +564.480 659.520 m +565.920 659.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +562.320 661.680 m +568.080 661.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +560.160 663.840 m +570.240 663.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +557.93 652.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 687.600 m +565.200 673.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +565.200 687.600 m +565.200 673.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +115.200 536.400 m +111.600 536.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +100.800 536.400 m +104.400 536.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +104.400 536.400 m +108.000 538.560 l +111.600 536.400 l +108.000 534.240 l +104.400 536.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +115.200 529.200 m +111.600 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +100.800 529.200 m +104.400 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +104.400 529.200 m +108.000 531.360 l +111.600 529.200 l +108.000 527.040 l +104.400 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +118.80 537.71 Td +(EIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 536.400 m +133.200 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +118.80 537.71 Td +(EIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 536.400 m +133.200 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +118.80 530.51 Td +(EIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 529.200 m +133.200 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +118.80 530.51 Td +(EIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +115.200 529.200 m +133.200 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +75.60 537.71 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.40 0.40 1.00 RG +0.00 g +[] 0 d +100.800 536.400 m +75.600 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +75.60 537.71 Td +(USB1_P) Tj +ET +1 J +1 j +0.72 w +0.40 0.40 1.00 RG +0.00 g +[] 0 d +100.800 536.400 m +75.600 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +75.60 530.51 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.40 0.40 1.00 RG +0.00 g +[] 0 d +100.800 529.200 m +75.600 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 0.000 1.000 rg +75.60 530.51 Td +(USB1_N) Tj +ET +1 J +1 j +0.72 w +0.40 0.40 1.00 RG +0.00 g +[] 0 d +100.800 529.200 m +75.600 529.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +579.60 298.80 14.40 -36.00 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +584.28 295.20 m 584.28 295.80 583.80 296.28 583.20 296.28 c +582.60 296.28 582.12 295.80 582.12 295.20 c +582.12 294.60 582.60 294.12 583.20 294.12 c +583.80 294.12 584.28 294.60 584.28 295.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +582.26 288.65 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +575.60 292.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 291.600 m +579.600 291.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +582.26 281.45 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +575.60 285.05 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 284.400 m +579.600 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +582.26 274.25 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +575.60 277.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 277.200 m +579.600 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +582.26 267.05 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +575.60 270.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 270.000 m +579.600 270.000 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +579.60 299.68 Td +(H8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 271.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 270.000 m +572.400 270.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 271.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 270.000 m +572.400 270.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 278.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 277.200 m +572.400 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 278.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 277.200 m +572.400 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 285.71 Td +(MONSCL) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 284.400 m +572.400 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 285.71 Td +(MONSCL) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 284.400 m +572.400 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 292.91 Td +(MONSDA) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 291.600 m +572.400 291.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +529.20 292.91 Td +(MONSDA) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +529.200 291.600 m +572.400 291.600 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +529.20 233.02 Td +(Debug Monitor) Tj +ET +7.20 w +BT +/F2 9.818181818181817 Tf +10.80 TL +0.000 g +532.80 250.36 Td +(ESP Monitor) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +370.80 493.20 136.80 -136.80 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +190.80 154.80 79.20 -64.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +195.48 151.20 m 195.48 151.80 195.00 152.28 194.40 152.28 c +193.80 152.28 193.32 151.80 193.32 151.20 c +193.32 150.60 193.80 150.12 194.40 150.12 c +195.00 150.12 195.48 150.60 195.48 151.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 144.65 Td +(DIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 148.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 147.600 m +190.800 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 137.45 Td +(GAIN_SLOT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 141.05 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 140.400 m +190.800 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 130.25 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 133.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 133.200 m +190.800 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 123.05 Td +(SD_MODE#) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 126.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 126.000 m +190.800 126.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 115.85 Td +(N.C.) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 119.45 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 118.800 m +190.800 118.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +180.720 121.680 m +186.480 115.920 l +180.720 115.920 m +186.480 121.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 108.65 Td +(N.C.) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 112.25 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 111.600 m +190.800 111.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +180.720 114.480 m +186.480 108.720 l +180.720 108.720 m +186.480 114.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 101.45 Td +(VDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 105.05 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 104.400 m +190.800 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +193.46 94.25 Td +(VDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +186.80 97.85 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +183.600 97.200 m +190.800 97.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +249.15 94.25 Td +(OUTP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 97.85 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 97.200 m +270.000 97.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +248.79 101.45 Td +(OUTN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 105.05 Td +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 104.400 m +270.000 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +252.79 108.65 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 112.25 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 111.600 m +270.000 111.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +254.25 115.85 Td +(N.C.) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 119.45 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 118.800 m +270.000 118.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +274.320 121.680 m +280.080 115.920 l +274.320 115.920 m +280.080 121.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +254.25 123.05 Td +(N.C.) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 126.65 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 126.000 m +270.000 126.000 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +274.320 128.880 m +280.080 123.120 l +274.320 123.120 m +280.080 128.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +246.24 130.25 Td +(LRCLK) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 133.85 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 133.200 m +270.000 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +252.79 137.45 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 141.05 Td +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 140.400 m +270.000 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +250.24 144.65 Td +(BCLK) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +270.36 148.25 Td +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +277.200 147.600 m +270.000 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 231.25 90.06 Tm +(EP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 228.37 81.34 Tm +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +230.400 82.800 m +230.400 90.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +190.80 156.11 Td +(U16) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +205.20 156.11 Td +(MAX98357AETE+T) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 148.91 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 147.600 m +162.000 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 148.91 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 147.600 m +162.000 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +140.40 112.91 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 104.400 m +183.600 97.200 l +S +172.800 104.400 m +183.600 104.400 l +S +147.600 104.400 m +172.800 104.400 l +S +140.400 104.400 m +140.400 111.600 l +S +140.400 104.400 m +147.600 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +140.40 112.91 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 104.400 m +183.600 97.200 l +S +172.800 104.400 m +183.600 104.400 l +S +147.600 104.400 m +172.800 104.400 l +S +140.400 104.400 m +140.400 111.600 l +S +140.400 104.400 m +147.600 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +284.40 148.91 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 147.600 m +298.800 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +284.40 148.91 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 147.600 m +298.800 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +284.40 134.51 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 133.200 m +298.800 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +284.40 134.51 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 133.200 m +298.800 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +277.20 98.51 Td +(NET15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +342.000 86.400 m +342.000 97.200 l +S +277.200 97.200 m +342.000 97.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +277.20 98.51 Td +(NET15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +342.000 86.400 m +342.000 97.200 l +S +277.200 97.200 m +342.000 97.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +277.20 105.71 Td +(NET16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +360.000 75.600 m +360.000 104.400 l +S +277.200 104.400 m +360.000 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +277.20 105.71 Td +(NET16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +360.000 75.600 m +360.000 104.400 l +S +277.200 104.400 m +360.000 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 141.71 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 140.400 m +162.000 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 141.71 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 140.400 m +162.000 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 156.11 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 154.800 m +93.600 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 156.11 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 154.800 m +93.600 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 148.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 147.600 m +93.600 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 148.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 147.600 m +93.600 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 141.71 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 140.400 m +93.600 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 141.71 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 140.400 m +93.600 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 134.51 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 133.200 m +93.600 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 134.51 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 133.200 m +93.600 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 127.31 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 126.000 m +93.600 126.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 127.31 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 126.000 m +93.600 126.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 120.11 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 118.800 m +93.600 118.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 120.11 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 118.800 m +93.600 118.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 112.91 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 111.600 m +93.600 111.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +79.20 112.91 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +61.200 111.600 m +93.600 111.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +313.200 140.400 m +320.400 140.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +320.400 133.200 m +320.400 147.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +326.880 139.680 m +326.880 141.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +324.720 137.520 m +324.720 143.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +322.560 135.360 m +322.560 145.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 333.49 133.13 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 140.400 m +313.200 140.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 140.400 m +313.200 140.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +302.400 111.600 m +309.600 111.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +309.600 104.400 m +309.600 118.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +316.080 110.880 m +316.080 112.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.920 108.720 m +313.920 114.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +311.760 106.560 m +311.760 116.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 322.69 104.33 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 111.600 m +302.400 111.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +277.200 111.600 m +302.400 111.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 134.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 133.200 m +162.000 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +162.00 134.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +183.600 133.200 m +162.000 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +111.34 127.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +136.800 126.000 m +144.000 126.000 l +S +144.000 126.000 m +183.600 126.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +111.34 127.31 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +136.800 126.000 m +144.000 126.000 l +S +144.000 126.000 m +183.600 126.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +144.000 154.800 m +144.000 147.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +144.000 126.000 m +144.000 133.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +141.12 147.60 5.76 -14.40 re +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +133.20 148.48 Td +(R28) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +126.00 141.71 Td +/F2 6.545454545454544 Tf +(1M) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +144.00 159.71 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +144.000 158.400 m +144.000 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +144.00 159.71 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +144.000 158.400 m +144.000 154.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +141.840 92.160 m +153.360 92.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +141.840 95.040 m +153.360 95.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +147.600 82.800 m +147.600 90.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +147.600 104.400 m +147.600 97.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +147.600 90.000 m +147.600 92.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +147.600 95.040 m +147.600 97.200 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +151.20 87.28 Td +(C35) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +147.60 76.91 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +172.800 95.040 m +172.800 97.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +172.800 90.000 m +172.800 92.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +172.800 104.400 m +172.800 97.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +172.800 82.800 m +172.800 90.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +167.040 95.040 m +178.560 95.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +167.040 92.160 m +178.560 92.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +176.40 84.11 Td +(C36) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +172.80 76.91 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +172.800 82.800 m +172.800 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +165.600 75.600 m +180.000 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +172.080 69.120 m +173.520 69.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +169.920 71.280 m +175.680 71.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +167.760 73.440 m +177.840 73.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +165.53 62.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +172.800 82.800 m +172.800 82.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +172.800 82.800 m +172.800 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +147.600 82.800 m +147.600 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +140.400 75.600 m +154.800 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +146.880 69.120 m +148.320 69.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +144.720 71.280 m +150.480 71.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +142.560 73.440 m +152.640 73.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +140.33 62.51 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +147.600 82.800 m +147.600 82.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +147.600 82.800 m +147.600 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +342.000 86.400 m +339.840 86.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +313.200 86.400 m +315.360 86.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +315.445 86.442 m +315.588 87.622 l +316.208 88.628 l +317.174 89.289 l +318.313 89.518 l +319.453 89.288 l +320.418 88.625 l +321.037 87.619 l +321.178 86.439 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +321.553 86.444 m +321.696 87.624 l +322.316 88.630 l +323.282 89.291 l +324.421 89.520 l +325.561 89.290 l +326.526 88.627 l +327.145 87.620 l +327.286 86.441 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +327.649 86.444 m +327.792 87.624 l +328.412 88.630 l +329.378 89.291 l +330.518 89.520 l +331.657 89.290 l +332.622 88.627 l +333.241 87.620 l +333.382 86.441 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +333.865 86.443 m +334.008 87.622 l +334.628 88.628 l +335.594 89.290 l +336.733 89.518 l +337.873 89.288 l +338.838 88.625 l +339.457 87.619 l +339.598 86.439 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +316.80 91.31 Td +(L1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +360.000 75.600 m +357.840 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +331.200 75.600 m +333.360 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +333.445 75.642 m +333.588 76.822 l +334.208 77.828 l +335.174 78.489 l +336.313 78.718 l +337.453 78.488 l +338.418 77.825 l +339.037 76.819 l +339.178 75.639 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +339.553 75.644 m +339.696 76.824 l +340.316 77.830 l +341.282 78.491 l +342.421 78.720 l +343.561 78.490 l +344.526 77.827 l +345.145 76.820 l +345.286 75.641 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +345.649 75.644 m +345.792 76.824 l +346.412 77.830 l +347.378 78.491 l +348.518 78.720 l +349.657 78.490 l +350.622 77.827 l +351.241 76.820 l +351.382 75.641 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +351.865 75.643 m +352.008 76.822 l +352.628 77.828 l +353.594 78.490 l +354.733 78.718 l +355.873 78.488 l +356.838 77.825 l +357.457 76.819 l +357.598 75.639 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +334.80 80.51 Td +(L2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +321.840 59.760 m +333.360 59.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +321.840 62.640 m +333.360 62.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.600 50.400 m +327.600 57.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.600 72.000 m +327.600 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +327.600 57.600 m +327.600 59.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +327.600 62.640 m +327.600 64.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +316.80 54.88 Td +(C37) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 340.69 54.00 Tm +(220pF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +307.440 59.760 m +318.960 59.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +307.440 62.640 m +318.960 62.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +313.200 50.400 m +313.200 57.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +313.200 72.000 m +313.200 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 57.600 m +313.200 59.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +313.200 62.640 m +313.200 64.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +306.00 54.88 Td +(C38) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 304.69 54.00 Tm +(220pF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +313.200 86.400 m +313.200 72.000 l +S +313.200 86.400 m +266.400 86.400 l +S +266.400 86.400 m +266.400 79.200 l +S +266.400 79.200 m +212.400 79.200 l +S +212.400 79.200 m +212.400 61.200 l +S +266.400 68.400 m +266.400 79.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +313.200 86.400 m +313.200 72.000 l +S +313.200 86.400 m +266.400 86.400 l +S +266.400 86.400 m +266.400 79.200 l +S +266.400 79.200 m +212.400 79.200 l +S +212.400 79.200 m +212.400 61.200 l +S +266.400 68.400 m +266.400 79.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +252.00 61.20 36.00 -21.60 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +260.28 57.60 m 260.28 58.20 259.80 58.68 259.20 58.68 c +258.60 58.68 258.12 58.20 258.12 57.60 c +258.12 57.00 258.60 56.52 259.20 56.52 c +259.80 56.52 260.28 57.00 260.28 57.60 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 269.35 54.90 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 265.75 61.56 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +266.400 68.400 m +266.400 61.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 276.55 54.90 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 272.95 61.56 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +273.600 68.400 m +273.600 61.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +253.29 48.83 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +246.62 52.43 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +244.800 50.400 m +252.000 50.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +280.32 48.83 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +286.98 52.43 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +295.200 50.400 m +288.000 50.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +252.00 33.71 Td +(CN1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +244.800 50.400 m +244.800 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +237.600 43.200 m +252.000 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +244.080 36.720 m +245.520 36.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +241.920 38.880 m +247.680 38.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +239.760 41.040 m +249.840 41.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +237.53 30.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +244.800 50.400 m +244.800 50.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +244.800 50.400 m +244.800 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +295.200 50.400 m +295.200 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +288.000 43.200 m +302.400 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +294.480 36.720 m +295.920 36.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +292.320 38.880 m +298.080 38.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +290.160 41.040 m +300.240 41.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +287.93 30.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +295.200 50.400 m +295.200 50.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +295.200 50.400 m +295.200 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +194.400 79.200 m +194.400 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +187.200 72.000 m +201.600 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +193.680 65.520 m +195.120 65.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +191.520 67.680 m +197.280 67.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +189.360 69.840 m +199.440 69.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +187.13 58.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +194.400 79.200 m +194.400 82.800 l +S +194.400 82.800 m +230.400 82.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +194.400 79.200 m +194.400 82.800 l +S +194.400 82.800 m +230.400 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +327.600 50.400 m +327.600 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +320.400 43.200 m +334.800 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +326.880 36.720 m +328.320 36.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +324.720 38.880 m +330.480 38.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +322.560 41.040 m +332.640 41.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +320.33 30.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +327.600 50.400 m +327.600 50.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +327.600 50.400 m +327.600 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +313.200 50.400 m +313.200 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +306.000 43.200 m +320.400 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +312.480 36.720 m +313.920 36.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +310.320 38.880 m +316.080 38.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +308.160 41.040 m +318.240 41.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +305.93 30.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +313.200 50.400 m +313.200 50.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +313.200 50.400 m +313.200 50.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +327.600 75.600 m +331.200 75.600 l +S +327.600 72.000 m +327.600 75.600 l +S +273.600 75.600 m +327.600 75.600 l +S +273.600 72.000 m +273.600 75.600 l +S +273.600 72.000 m +273.600 68.400 l +S +219.600 72.000 m +273.600 72.000 l +S +219.600 72.000 m +219.600 61.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +327.600 75.600 m +331.200 75.600 l +S +327.600 72.000 m +327.600 75.600 l +S +273.600 75.600 m +327.600 75.600 l +S +273.600 72.000 m +273.600 75.600 l +S +273.600 72.000 m +273.600 68.400 l +S +219.600 72.000 m +273.600 72.000 l +S +219.600 72.000 m +219.600 61.200 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +133.20 38.62 Td +(Amplifier) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +28.80 176.40 342.00 -147.60 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1234.80 618.22 Td +(ESP - Pico Bridge) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1303.20 771.71 Td +(GPIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1296.000 770.400 m +1317.600 770.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1303.20 771.71 Td +(GPIO0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1296.000 770.400 m +1317.600 770.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1299.60 760.91 Td +(GPIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1296.000 759.600 m +1317.600 759.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1299.60 760.91 Td +(GPIO1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1296.000 759.600 m +1317.600 759.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1249.20 645.71 Td +(EIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1249.200 644.400 m +1270.800 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1249.20 645.71 Td +(EIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1249.200 644.400 m +1270.800 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1249.20 634.91 Td +(EIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1249.200 633.600 m +1270.800 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1249.20 634.91 Td +(EIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1249.200 633.600 m +1270.800 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1328.40 771.71 Td +(Pico TX) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1328.40 760.91 Td +(Pico RX) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1220.40 634.91 Td +(ESP TX) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1220.40 645.71 Td +(ESP RX) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +1202.40 658.80 165.60 -46.80 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1274.40 530.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1274.400 529.200 m +1314.000 529.200 l +S +1317.600 529.200 m +1314.000 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1274.40 530.51 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1274.400 529.200 m +1314.000 529.200 l +S +1317.600 529.200 m +1314.000 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1274.40 537.71 Td +(MICSD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1274.400 536.400 m +1314.000 536.400 l +S +1317.600 536.400 m +1314.000 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1274.40 537.71 Td +(MICSD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1274.400 536.400 m +1314.000 536.400 l +S +1317.600 536.400 m +1314.000 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 516.11 Td +(MICSCK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 514.800 m +1278.000 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 516.11 Td +(MICSCK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 514.800 m +1278.000 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 508.91 Td +(MICWS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 507.600 m +1278.000 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 508.91 Td +(MICWS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 507.600 m +1278.000 507.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1260.000 522.000 m +1260.000 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1267.200 529.200 m +1252.800 529.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1260.720 535.680 m +1259.280 535.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1262.880 533.520 m +1257.120 533.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1265.040 531.360 m +1254.960 531.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1252.73 537.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 522.000 m +1260.000 522.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 522.000 m +1260.000 522.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1292.400 543.600 m +1292.400 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1299.600 550.800 m +1285.200 550.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1293.120 557.280 m +1291.680 557.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1295.280 555.120 m +1289.520 555.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1297.440 552.960 m +1287.360 552.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1285.13 559.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 543.600 m +1292.400 543.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 543.600 m +1292.400 543.600 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1220.40 582.22 Td +(Mic Connector) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +1198.80 604.80 169.20 -147.60 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 75.600 m +75.600 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 75.600 m +82.800 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +82.800 75.600 m +79.200 73.440 l +75.600 75.600 l +79.200 77.760 l +82.800 75.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 76.91 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 75.600 m +72.000 75.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 76.91 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 75.600 m +72.000 75.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 76.91 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +86.400 75.600 m +118.800 75.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 76.91 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +86.400 75.600 m +118.800 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 61.200 m +82.800 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 61.200 m +75.600 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +75.600 61.200 m +79.200 63.360 l +82.800 61.200 l +79.200 59.040 l +75.600 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 54.000 m +82.800 54.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 54.000 m +75.600 54.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +75.600 54.000 m +79.200 56.160 l +82.800 54.000 l +79.200 51.840 l +75.600 54.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 46.800 m +82.800 46.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 46.800 m +75.600 46.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +75.600 46.800 m +79.200 48.960 l +82.800 46.800 l +79.200 44.640 l +75.600 46.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 39.600 m +82.800 39.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 39.600 m +75.600 39.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +75.600 39.600 m +79.200 41.760 l +82.800 39.600 l +79.200 37.440 l +75.600 39.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 62.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 61.200 m +86.400 61.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 62.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 61.200 m +86.400 61.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 55.31 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 54.000 m +86.400 54.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +93.34 55.31 Td +(MAXDIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 54.000 m +86.400 54.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +87.52 48.11 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 46.800 m +86.400 46.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +87.52 48.11 Td +(MAXBCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 46.800 m +86.400 46.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +83.52 40.91 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 39.600 m +86.400 39.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +83.52 40.91 Td +(MAXLRCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +118.800 39.600 m +86.400 39.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 40.91 Td +(EIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 39.600 m +72.000 39.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 40.91 Td +(EIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 39.600 m +72.000 39.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 48.11 Td +(EIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 46.800 m +72.000 46.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 48.11 Td +(EIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 46.800 m +72.000 46.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 55.31 Td +(EIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 54.000 m +72.000 54.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 55.31 Td +(EIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 54.000 m +72.000 54.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 62.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 61.200 m +72.000 61.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 62.51 Td +(VDD3V3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +50.400 61.200 m +72.000 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +86.400 68.400 m +82.800 68.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +72.000 68.400 m +75.600 68.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +75.600 68.400 m +79.200 70.560 l +82.800 68.400 l +79.200 66.240 l +75.600 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +102.80 69.71 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +86.400 68.400 m +118.800 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +102.80 69.71 Td +(GAIN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +86.400 68.400 m +118.800 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 69.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +72.000 68.400 m +50.400 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +50.40 69.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +72.000 68.400 m +50.400 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +558.94 292.91 Td +(SDA) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +559.67 285.71 Td +(SCL) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +560.76 278.51 Td +(3V3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +557.86 271.31 Td +(GND) Tj +ET +7.20 w +BT +/F2 3.272727272727272 Tf +3.60 TL +0.000 g +1281.60 551.45 Td +(LR) Tj +ET +7.20 w +BT +/F2 3.272727272727272 Tf +3.60 TL +0.000 g +1281.60 544.25 Td +(WS) Tj +ET +7.20 w +BT +/F2 3.272727272727272 Tf +3.60 TL +0.000 g +1281.60 537.05 Td +(SCK) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1317.60 748.80 14.40 -57.60 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1322.28 745.20 m 1322.28 745.80 1321.80 746.28 1321.20 746.28 c +1320.60 746.28 1320.12 745.80 1320.12 745.20 c +1320.12 744.60 1320.60 744.12 1321.20 744.12 c +1321.80 744.12 1322.28 744.60 1322.28 745.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 738.65 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 742.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 741.600 m +1317.600 741.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 731.45 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 735.05 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 734.400 m +1317.600 734.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 724.25 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 727.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 727.200 m +1317.600 727.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 717.05 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 720.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 720.000 m +1317.600 720.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 709.85 Td +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 713.45 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 712.800 m +1317.600 712.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 702.65 Td +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 706.25 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 705.600 m +1317.600 705.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1320.26 695.45 Td +(7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1313.60 699.05 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1310.400 698.400 m +1317.600 698.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1317.60 750.11 Td +(U18) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1292.40 645.71 Td +(GPIO4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1285.200 644.400 m +1306.800 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1292.40 645.71 Td +(GPIO4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1285.200 644.400 m +1306.800 644.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1292.40 634.91 Td +(GPIO5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1306.800 633.600 m +1285.200 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1292.40 634.91 Td +(GPIO5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1306.800 633.600 m +1285.200 633.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 616.91 Td +(GPIO4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 615.600 m +882.000 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 616.91 Td +(GPIO4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 615.600 m +882.000 615.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 609.71 Td +(GPIO5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 608.400 m +882.000 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 609.71 Td +(GPIO5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 608.400 m +882.000 608.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 602.51 Td +(GPIO6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 601.200 m +882.000 601.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 602.51 Td +(GPIO6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 601.200 m +882.000 601.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 595.31 Td +(GPIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 594.000 m +882.000 594.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 595.31 Td +(GPIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 594.000 m +882.000 594.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 588.11 Td +(GPIO8) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 586.800 m +882.000 586.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 588.11 Td +(GPIO8) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 586.800 m +882.000 586.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 580.91 Td +(GPIO9) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 579.600 m +882.000 579.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +889.20 580.91 Td +(GPIO9) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +910.800 579.600 m +882.000 579.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1314.00 645.71 Td +(Pico TX1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1314.00 634.91 Td +(Pico RX1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1260.00 771.71 Td +(RXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1281.600 770.400 m +1260.000 770.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1260.00 771.71 Td +(RXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1281.600 770.400 m +1260.000 770.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1260.00 760.91 Td +(TXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1281.600 759.600 m +1260.000 759.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1260.00 760.91 Td +(TXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1281.600 759.600 m +1260.000 759.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1227.60 771.71 Td +(Grove RX) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1227.60 760.91 Td +(Grove TX) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 699.71 Td +(TXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1288.800 698.400 m +1238.400 698.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 699.71 Td +(TXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1288.800 698.400 m +1238.400 698.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1296.00 688.91 Td +(RXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 698.400 m +1303.200 698.400 l +S +1303.200 698.400 m +1303.200 687.600 l +S +1303.200 687.600 m +1296.000 687.600 l +S +1339.200 698.400 m +1310.400 698.400 l +S +1310.400 698.400 m +1310.400 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1296.00 688.91 Td +(RXD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 698.400 m +1303.200 698.400 l +S +1303.200 698.400 m +1303.200 687.600 l +S +1303.200 687.600 m +1296.000 687.600 l +S +1339.200 698.400 m +1310.400 698.400 l +S +1310.400 698.400 m +1310.400 687.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 742.91 Td +(VSYS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1292.400 741.600 m +1238.400 741.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1278.00 742.91 Td +(VSYS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1292.400 741.600 m +1238.400 741.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1288.800 734.400 m +1288.800 727.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1281.600 727.200 m +1296.000 727.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1288.080 720.720 m +1289.520 720.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1285.920 722.880 m +1291.680 722.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1283.760 725.040 m +1293.840 725.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1281.53 714.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1288.800 734.400 m +1238.400 734.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1288.800 734.400 m +1238.400 734.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 705.600 m +1270.800 705.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 705.600 m +1270.800 705.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 712.800 m +1270.800 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 712.800 m +1270.800 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 720.000 m +1270.800 720.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 720.000 m +1270.800 720.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 727.200 m +1270.800 727.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1238.400 727.200 m +1270.800 727.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 741.600 m +1339.200 741.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 741.600 m +1339.200 741.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 734.400 m +1339.200 734.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 734.400 m +1339.200 734.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 727.200 m +1339.200 727.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 727.200 m +1339.200 727.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 720.000 m +1339.200 720.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 720.000 m +1339.200 720.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 712.800 m +1339.200 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 712.800 m +1339.200 712.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 705.600 m +1339.200 705.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1310.400 705.600 m +1339.200 705.600 l +S +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +1202.40 788.40 165.60 -122.40 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1238.40 675.82 Td +(Grove Vision AI V2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.800 0.000 rg +914.40 570.11 Td +(Monitor) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.800 0.000 rg +914.40 562.91 Td +(Monitor) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 1.000 rg +914.40 645.71 Td +(ESP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 1.000 rg +914.40 638.51 Td +(ESP) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +914.40 613.31 Td +(Grove) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +1.000 0.600 0.000 rg +914.40 606.11 Td +(Grove) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +892.80 309.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +897.48 298.80 m 897.48 299.40 897.00 299.88 896.40 299.88 c +895.80 299.88 895.32 299.40 895.32 298.80 c +895.32 298.20 895.80 297.72 896.40 297.72 c +897.00 297.72 897.48 298.20 897.48 298.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 902.95 297.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 899.35 291.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +900.000 288.000 m +900.000 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 917.35 303.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 913.75 309.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 316.800 m +914.400 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 910.15 297.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 906.55 291.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +907.200 288.000 m +907.200 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 910.15 303.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 906.55 309.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +907.200 316.800 m +907.200 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 917.35 297.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 913.75 291.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 288.000 m +914.400 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 902.95 303.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 899.35 309.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +900.000 316.800 m +900.000 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +925.20 303.71 Td +(U22) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 321.71 Td +(GPIO6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 316.800 m +900.000 320.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 321.71 Td +(GPIO6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 316.800 m +900.000 320.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 278.51 Td +(GPIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 288.000 m +900.000 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 278.51 Td +(GPIO7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 288.000 m +900.000 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 598.91 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 591.71 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 584.51 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 577.31 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 555.71 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 548.51 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 541.31 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 534.11 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 526.91 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 519.71 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 512.51 Td +(Servos) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.800 0.200 0.000 rg +914.40 505.31 Td +(Servos) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +892.80 255.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +897.48 244.80 m 897.48 245.40 897.00 245.88 896.40 245.88 c +895.80 245.88 895.32 245.40 895.32 244.80 c +895.32 244.20 895.80 243.72 896.40 243.72 c +897.00 243.72 897.48 244.20 897.48 244.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 902.95 243.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 899.35 237.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +900.000 234.000 m +900.000 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 917.35 249.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 913.75 255.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 262.800 m +914.400 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 910.15 243.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 906.55 237.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +907.200 234.000 m +907.200 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 910.15 249.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 906.55 255.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +907.200 262.800 m +907.200 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 917.35 243.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 913.75 237.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 234.000 m +914.400 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 902.95 249.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 899.35 255.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +900.000 262.800 m +900.000 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +925.20 249.71 Td +(U2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 267.71 Td +(GPIO8) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 262.800 m +900.000 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 267.71 Td +(GPIO8) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 262.800 m +900.000 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 224.51 Td +(GPIO9) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 234.000 m +900.000 230.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +879.99 224.51 Td +(GPIO9) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +900.000 234.000 m +900.000 230.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +954.00 255.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +958.68 244.80 m 958.68 245.40 958.20 245.88 957.60 245.88 c +957.00 245.88 956.52 245.40 956.52 244.80 c +956.52 244.20 957.00 243.72 957.60 243.72 c +958.20 243.72 958.68 244.20 958.68 244.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 964.15 243.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 960.55 237.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +961.200 234.000 m +961.200 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 978.55 249.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 974.95 255.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 262.800 m +975.600 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 971.35 243.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 967.75 237.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +968.400 234.000 m +968.400 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 971.35 249.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 967.75 255.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +968.400 262.800 m +968.400 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 978.55 243.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 974.95 237.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 234.000 m +975.600 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 964.15 249.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 960.55 255.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +961.200 262.800 m +961.200 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +986.40 249.71 Td +(U4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 267.71 Td +(GPIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 266.400 m +961.200 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 267.71 Td +(GPIO14) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 266.400 m +961.200 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 224.51 Td +(GPIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 230.400 m +961.200 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 224.51 Td +(GPIO15) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 230.400 m +961.200 234.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +954.00 309.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +958.68 298.80 m 958.68 299.40 958.20 299.88 957.60 299.88 c +957.00 299.88 956.52 299.40 956.52 298.80 c +956.52 298.20 957.00 297.72 957.60 297.72 c +958.20 297.72 958.68 298.20 958.68 298.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 964.15 297.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 960.55 291.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +961.200 288.000 m +961.200 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 978.55 303.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 974.95 309.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 316.800 m +975.600 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 971.35 297.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 967.75 291.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +968.400 288.000 m +968.400 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 971.35 303.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 967.75 309.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +968.400 316.800 m +968.400 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 978.55 297.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 974.95 291.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 288.000 m +975.600 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 964.15 303.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 960.55 309.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +961.200 316.800 m +961.200 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +986.40 303.71 Td +(U5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 321.71 Td +(GPIO12) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 316.800 m +961.200 320.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 321.71 Td +(GPIO12) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 316.800 m +961.200 320.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 278.51 Td +(GPIO13) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 288.000 m +961.200 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +937.55 278.51 Td +(GPIO13) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +961.200 288.000 m +961.200 284.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1015.20 255.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1019.88 244.80 m 1019.88 245.40 1019.40 245.88 1018.80 245.88 c +1018.20 245.88 1017.72 245.40 1017.72 244.80 c +1017.72 244.20 1018.20 243.72 1018.80 243.72 c +1019.40 243.72 1019.88 244.20 1019.88 244.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1025.35 243.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1021.75 237.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 234.000 m +1022.400 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1039.75 249.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1036.15 255.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 262.800 m +1036.800 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1032.55 243.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1028.95 237.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 234.000 m +1029.600 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1032.55 249.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1028.95 255.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 262.800 m +1029.600 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1039.75 243.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1036.15 237.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 234.000 m +1036.800 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1025.35 249.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1021.75 255.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 262.800 m +1022.400 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1047.60 249.71 Td +(U23) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 267.71 Td +(GPIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 262.800 m +1022.400 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 267.71 Td +(GPIO18) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 262.800 m +1022.400 266.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 224.51 Td +(GPIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 234.000 m +1022.400 230.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 224.51 Td +(GPIO19) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 234.000 m +1022.400 230.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1015.20 309.60 28.80 -14.40 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1019.88 298.80 m 1019.88 299.40 1019.40 299.88 1018.80 299.88 c +1018.20 299.88 1017.72 299.40 1017.72 298.80 c +1017.72 298.20 1018.20 297.72 1018.80 297.72 c +1019.40 297.72 1019.88 298.20 1019.88 298.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1025.35 297.86 Tm +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1021.75 291.20 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 288.000 m +1022.400 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1039.75 303.30 Tm +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1036.15 309.96 Tm +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 316.800 m +1036.800 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1032.55 297.86 Tm +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1028.95 291.20 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 288.000 m +1029.600 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1032.55 303.30 Tm +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1028.95 309.96 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1029.600 316.800 m +1029.600 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1039.75 297.86 Tm +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1036.15 291.20 Tm +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 288.000 m +1036.800 295.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1025.35 303.30 Tm +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 1021.75 309.96 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1022.400 316.800 m +1022.400 309.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1047.60 303.71 Td +(U24) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 321.71 Td +(GPIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 320.400 m +1022.400 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 321.71 Td +(GPIO16) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 320.400 m +1022.400 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 278.51 Td +(GPIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 284.400 m +1022.400 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +998.75 278.51 Td +(GPIO17) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1022.400 284.400 m +1022.400 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 316.800 m +921.600 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +921.600 309.600 m +921.600 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +928.080 316.080 m +928.080 317.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +925.920 313.920 m +925.920 319.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +923.760 311.760 m +923.760 321.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 934.69 309.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 316.800 m +914.400 316.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 316.800 m +914.400 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 288.000 m +921.600 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +921.600 280.800 m +921.600 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +928.080 287.280 m +928.080 288.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +925.920 285.120 m +925.920 290.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +923.760 282.960 m +923.760 293.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 934.69 280.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 288.000 m +914.400 288.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 288.000 m +914.400 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 262.800 m +921.600 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +921.600 255.600 m +921.600 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +928.080 262.080 m +928.080 263.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +925.920 259.920 m +925.920 265.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +923.760 257.760 m +923.760 267.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 934.69 255.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 262.800 m +914.400 262.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 262.800 m +914.400 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +914.400 234.000 m +921.600 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +921.600 226.800 m +921.600 241.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +928.080 233.280 m +928.080 234.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +925.920 231.120 m +925.920 236.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +923.760 228.960 m +923.760 239.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 934.69 226.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 234.000 m +914.400 234.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +914.400 234.000 m +914.400 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 262.800 m +982.800 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +982.800 255.600 m +982.800 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +989.280 262.080 m +989.280 263.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +987.120 259.920 m +987.120 265.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +984.960 257.760 m +984.960 267.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 995.89 255.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 262.800 m +975.600 262.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 262.800 m +975.600 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 234.000 m +982.800 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +982.800 226.800 m +982.800 241.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +989.280 233.280 m +989.280 234.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +987.120 231.120 m +987.120 236.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +984.960 228.960 m +984.960 239.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 995.89 226.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 234.000 m +975.600 234.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 234.000 m +975.600 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 288.000 m +982.800 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +982.800 280.800 m +982.800 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +989.280 287.280 m +989.280 288.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +987.120 285.120 m +987.120 290.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +984.960 282.960 m +984.960 293.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 995.89 280.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 288.000 m +975.600 288.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 288.000 m +975.600 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +975.600 316.800 m +982.800 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +982.800 309.600 m +982.800 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +989.280 316.080 m +989.280 317.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +987.120 313.920 m +987.120 319.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +984.960 311.760 m +984.960 321.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 995.89 309.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 316.800 m +975.600 316.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +975.600 316.800 m +975.600 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 316.800 m +1044.000 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1044.000 309.600 m +1044.000 324.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1050.480 316.080 m +1050.480 317.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1048.320 313.920 m +1048.320 319.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1046.160 311.760 m +1046.160 321.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1057.09 309.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 316.800 m +1036.800 316.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 316.800 m +1036.800 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 288.000 m +1044.000 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1044.000 280.800 m +1044.000 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1050.480 287.280 m +1050.480 288.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1048.320 285.120 m +1048.320 290.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1046.160 282.960 m +1046.160 293.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1057.09 280.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 288.000 m +1036.800 288.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 288.000 m +1036.800 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 262.800 m +1044.000 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1044.000 255.600 m +1044.000 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1050.480 262.080 m +1050.480 263.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1048.320 259.920 m +1048.320 265.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1046.160 257.760 m +1046.160 267.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1057.09 255.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 262.800 m +1036.800 262.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 262.800 m +1036.800 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1036.800 234.000 m +1044.000 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1044.000 226.800 m +1044.000 241.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1050.480 233.280 m +1050.480 234.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1048.320 231.120 m +1048.320 236.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1046.160 228.960 m +1046.160 239.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 1057.09 226.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 234.000 m +1036.800 234.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1036.800 234.000 m +1036.800 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 324.000 m +907.200 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 324.000 m +907.200 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 284.400 m +907.200 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 284.400 m +907.200 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 324.000 m +968.400 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 324.000 m +968.400 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 324.000 m +1029.600 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 325.31 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 324.000 m +1029.600 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 284.400 m +1029.600 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 284.400 m +1029.600 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 284.400 m +968.400 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 278.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 284.400 m +968.400 288.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 266.400 m +907.200 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 266.400 m +907.200 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 230.400 m +907.200 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +907.20 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +907.200 230.400 m +907.200 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 266.400 m +968.400 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 266.400 m +968.400 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 266.400 m +1029.600 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 267.71 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 266.400 m +1029.600 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 230.400 m +1029.600 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +1029.60 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1029.600 230.400 m +1029.600 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 230.400 m +968.400 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +968.40 224.51 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +968.400 230.400 m +968.400 234.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +457.200 136.800 m +446.400 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +428.400 136.800 m +439.200 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +437.040 141.120 m +437.040 141.840 l +438.480 141.840 l +438.480 131.040 l +439.920 131.040 l +439.920 131.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +446.400 141.120 m +439.200 136.800 l +446.400 131.760 l +446.400 141.120 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +435.60 145.31 Td +(D2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +432.00 123.71 Td +(B5819WS) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +457.200 104.400 m +446.400 104.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +428.400 104.400 m +439.200 104.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +437.040 108.720 m +437.040 109.440 l +438.480 109.440 l +438.480 98.640 l +439.920 98.640 l +439.920 99.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +446.400 108.720 m +439.200 104.400 l +446.400 99.360 l +446.400 108.720 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +435.60 112.91 Td +(D6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +432.00 91.31 Td +(B5819WS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +406.80 145.31 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 144.000 m +428.400 136.800 l +S +428.400 144.000 m +417.600 144.000 l +S +417.600 144.000 m +396.000 144.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +406.80 145.31 Td +(VBUSINESP) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 144.000 m +428.400 136.800 l +S +428.400 144.000 m +417.600 144.000 l +S +417.600 144.000 m +396.000 144.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +396.00 105.71 Td +(VBUS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 104.400 m +417.600 104.400 l +S +417.600 104.400 m +396.000 104.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +396.00 105.71 Td +(VBUS) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 104.400 m +417.600 104.400 l +S +417.600 104.400 m +396.000 104.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +446.400 69.840 m +439.200 64.800 l +446.400 59.760 l +446.400 69.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +439.200 64.800 m +435.600 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +450.000 64.800 m +446.400 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +437.760 68.400 m +437.760 69.840 l +439.200 69.840 l +439.200 59.760 l +440.640 59.760 l +440.640 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +457.200 64.800 m +450.000 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +428.400 64.800 m +435.600 64.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +435.60 73.31 Td +(D7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +439.20 51.71 Td +(SS1045-SMB) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +396.00 66.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 64.800 m +421.200 64.800 l +S +421.200 64.800 m +396.000 64.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +396.00 66.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +428.400 64.800 m +421.200 64.800 l +S +421.200 64.800 m +396.000 64.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +411.840 131.760 m +423.360 131.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +411.840 134.640 m +423.360 134.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 122.400 m +417.600 129.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 144.000 m +417.600 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +417.600 129.600 m +417.600 131.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +417.600 134.640 m +417.600 136.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +421.20 126.88 Td +(C2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +417.60 138.11 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +411.840 92.160 m +423.360 92.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +411.840 95.040 m +423.360 95.040 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 82.800 m +417.600 90.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 104.400 m +417.600 97.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +417.600 90.000 m +417.600 92.160 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +417.600 95.040 m +417.600 97.200 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +421.20 87.28 Td +(C10) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +417.60 98.51 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 82.800 m +410.400 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +410.400 90.000 m +410.400 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +403.920 83.520 m +403.920 82.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +406.080 85.680 m +406.080 79.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 87.840 m +408.240 77.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 401.89 75.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +417.600 82.800 m +417.600 82.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +417.600 82.800 m +417.600 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +417.600 122.400 m +410.400 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +410.400 129.600 m +410.400 115.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +403.920 123.120 m +403.920 121.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +406.080 125.280 m +406.080 119.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +408.240 127.440 m +408.240 117.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 401.89 115.13 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +417.600 122.400 m +417.600 122.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +417.600 122.400 m +417.600 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +414.000 43.200 m +406.800 43.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +406.800 50.400 m +406.800 36.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +400.320 43.920 m +400.320 42.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +402.480 46.080 m +402.480 40.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +404.640 48.240 m +404.640 38.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 398.29 35.93 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +414.000 43.200 m +421.200 43.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +414.000 43.200 m +421.200 43.200 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +493.20 53.02 Td +(Main) Tj +T* (Power) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +378.00 176.40 172.80 -147.60 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +948.960 195.840 m +937.440 195.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +943.200 205.200 m +943.200 198.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +943.200 183.600 m +943.200 190.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +943.200 198.000 m +943.200 195.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +943.200 192.960 m +943.200 190.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +948.473 190.895 m +946.943 192.017 l +945.227 192.699 l +943.431 192.957 l +941.628 192.803 l +939.883 192.230 l +938.294 191.219 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +945.360 201.600 m +945.360 198.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +946.800 200.160 m +943.920 200.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +946.80 202.91 Td +(C3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +957.60 195.71 Td +(220uF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +943.20 210.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +943.200 208.800 m +943.200 205.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +943.20 210.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +943.200 208.800 m +943.200 205.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +943.200 183.600 m +943.200 176.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +936.000 176.400 m +950.400 176.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +942.480 169.920 m +943.920 169.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +940.320 172.080 m +946.080 172.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +938.160 174.240 m +948.240 174.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +935.93 163.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +943.200 183.600 m +943.200 183.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +943.200 183.600 m +943.200 183.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +902.160 195.840 m +890.640 195.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 205.200 m +896.400 198.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 183.600 m +896.400 190.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +896.400 198.000 m +896.400 195.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +896.400 192.960 m +896.400 190.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +901.673 190.895 m +900.143 192.017 l +898.427 192.699 l +896.631 192.957 l +894.828 192.803 l +893.083 192.230 l +891.494 191.219 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +898.560 201.600 m +898.560 198.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +900.000 200.160 m +897.120 200.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +900.00 202.91 Td +(C21) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +910.80 195.71 Td +(220uF) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +896.40 210.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 205.200 m +896.400 208.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +896.40 210.11 Td +(V+) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 205.200 m +896.400 208.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +896.400 183.600 m +896.400 176.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +889.200 176.400 m +903.600 176.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +895.680 169.920 m +897.120 169.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +893.520 172.080 m +899.280 172.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +891.360 174.240 m +901.440 174.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +889.13 163.31 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 183.600 m +896.400 183.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +896.400 183.600 m +896.400 183.600 l +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1006.86 179.02 Td +(Servos) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +874.80 338.40 190.80 -180.00 re +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 244.800 m +421.200 244.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +432.000 244.800 m +421.200 244.800 l +S +2 J +0 j +72 M +0.72 w +0.40 G +[] 0 d +993.60 522.00 194.40 -97.20 re +S +2 J +0 j +72 M +1.44 w +0.00 G +[] 0 d +633.60 788.40 561.60 -442.80 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +594.00 148.91 Td +(GPIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +594.000 147.600 m +594.000 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +594.00 148.91 Td +(GPIO20) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +594.000 147.600 m +594.000 140.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1285.200 644.400 m +1281.600 644.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1270.800 644.400 m +1274.400 644.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1274.400 644.400 m +1278.000 646.560 l +1281.600 644.400 l +1278.000 642.240 l +1274.400 644.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1285.200 633.600 m +1281.600 633.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1270.800 633.600 m +1274.400 633.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1274.400 633.600 m +1278.000 635.760 l +1281.600 633.600 l +1278.000 631.440 l +1274.400 633.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1296.000 770.400 m +1292.400 770.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1281.600 770.400 m +1285.200 770.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1285.200 770.400 m +1288.800 772.560 l +1292.400 770.400 l +1288.800 768.240 l +1285.200 770.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1296.000 759.600 m +1292.400 759.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1281.600 759.600 m +1285.200 759.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1285.200 759.600 m +1288.800 761.760 l +1292.400 759.600 l +1288.800 757.440 l +1285.200 759.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 285.71 Td +(CAMD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 284.400 m +766.800 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 285.71 Td +(CAMD2) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 284.400 m +766.800 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 278.51 Td +(CAMD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 277.200 m +766.800 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 278.51 Td +(CAMD1) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 277.200 m +766.800 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 271.31 Td +(CAMD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 270.000 m +766.800 270.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 271.31 Td +(CAMD3) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 270.000 m +766.800 270.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 264.11 Td +(CAMD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 262.800 m +766.800 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 264.11 Td +(CAMD0) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 262.800 m +766.800 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 256.91 Td +(CAMD4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 255.600 m +766.800 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 256.91 Td +(CAMD4) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 255.600 m +766.800 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +774.76 249.71 Td +(CAMPCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +756.000 248.400 m +817.200 248.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +774.76 249.71 Td +(CAMPCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +756.000 248.400 m +817.200 248.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 242.51 Td +(CAMD5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 241.200 m +766.800 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 242.51 Td +(CAMD5) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 241.200 m +766.800 241.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 234.000 m +766.800 234.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 234.000 m +766.800 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 228.11 Td +(CAMD6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 226.800 m +766.800 226.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +794.29 228.11 Td +(CAMD6) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 226.800 m +766.800 226.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +785.56 220.91 Td +(CAMXCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 219.600 m +784.800 219.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +785.56 220.91 Td +(CAMXCLK) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 219.600 m +784.800 219.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +790.69 213.71 Td +(CAMD7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 212.400 m +784.800 212.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +790.69 213.71 Td +(CAMD7) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 212.400 m +784.800 212.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 205.200 m +770.400 205.200 l +S +756.000 205.200 m +770.400 205.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 205.200 m +770.400 205.200 l +S +756.000 205.200 m +770.400 205.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +774.000 187.200 m +763.200 187.200 l +S +774.000 187.200 m +774.000 198.000 l +S +817.200 198.000 m +774.000 198.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +774.000 187.200 m +763.200 187.200 l +S +774.000 187.200 m +774.000 198.000 l +S +817.200 198.000 m +774.000 198.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +784.84 192.11 Td +(CAMHREF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 190.800 m +784.800 190.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +784.84 192.11 Td +(CAMHREF) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 190.800 m +784.800 190.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +788.40 184.91 Td +(PWDN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +759.600 183.600 m +817.200 183.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +788.40 184.91 Td +(PWDN) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +759.600 183.600 m +817.200 183.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +780.11 177.71 Td +(CAMVSYNC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +766.800 176.400 m +817.200 176.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +780.11 177.71 Td +(CAMVSYNC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +766.800 176.400 m +817.200 176.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +788.40 170.51 Td +(CAMRST) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 169.200 m +784.800 169.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +788.40 170.51 Td +(CAMRST) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 169.200 m +784.800 169.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +786.65 163.31 Td +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 162.000 m +784.800 162.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +786.65 163.31 Td +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 162.000 m +784.800 162.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +766.800 154.800 m +817.200 154.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +766.800 154.800 m +817.200 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +786.65 148.91 Td +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 147.600 m +781.200 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +786.65 148.91 Td +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +817.200 147.600 m +781.200 147.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +730.800 140.400 m +730.800 118.800 l +S +730.800 140.400 m +817.200 140.400 l +S +730.800 183.600 m +730.800 140.400 l +S +730.800 183.600 m +730.800 205.200 l +S +730.800 205.200 m +734.400 205.200 l +S +730.800 248.400 m +730.800 205.200 l +S +734.400 248.400 m +730.800 248.400 l +S +817.200 118.800 m +730.800 118.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +730.800 140.400 m +730.800 118.800 l +S +730.800 140.400 m +817.200 140.400 l +S +730.800 183.600 m +730.800 140.400 l +S +730.800 183.600 m +730.800 205.200 l +S +730.800 205.200 m +734.400 205.200 l +S +730.800 248.400 m +730.800 205.200 l +S +734.400 248.400 m +730.800 248.400 l +S +817.200 118.800 m +730.800 118.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +730.800 118.800 m +723.600 118.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +723.600 126.000 m +723.600 111.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +717.120 119.520 m +717.120 118.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +719.280 121.680 m +719.280 115.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +721.440 123.840 m +721.440 113.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 715.09 111.53 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1108.08 302.40 m 1108.08 307.97 1103.57 312.48 1098.00 312.48 c +1092.43 312.48 1087.92 307.97 1087.92 302.40 c +1087.92 296.83 1092.43 292.32 1098.00 292.32 c +1103.57 292.32 1108.08 296.83 1108.08 302.40 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1113.84 302.40 m 1113.84 311.15 1106.75 318.24 1098.00 318.24 c +1089.25 318.24 1082.16 311.15 1082.16 302.40 c +1082.16 293.65 1089.25 286.56 1098.00 286.56 c +1106.75 286.56 1113.84 293.65 1113.84 302.40 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1128.96 300.11 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1119.56 303.71 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1112.400 302.400 m +1126.800 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1083.60 321.71 Td +(MH1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1158.48 302.40 m 1158.48 307.97 1153.97 312.48 1148.40 312.48 c +1142.83 312.48 1138.32 307.97 1138.32 302.40 c +1138.32 296.83 1142.83 292.32 1148.40 292.32 c +1153.97 292.32 1158.48 296.83 1158.48 302.40 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1164.24 302.40 m 1164.24 311.15 1157.15 318.24 1148.40 318.24 c +1139.65 318.24 1132.56 311.15 1132.56 302.40 c +1132.56 293.65 1139.65 286.56 1148.40 286.56 c +1157.15 286.56 1164.24 293.65 1164.24 302.40 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1179.36 300.11 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1169.96 303.71 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 302.400 m +1177.200 302.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1134.00 321.71 Td +(MH2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1108.08 259.20 m 1108.08 264.77 1103.57 269.28 1098.00 269.28 c +1092.43 269.28 1087.92 264.77 1087.92 259.20 c +1087.92 253.63 1092.43 249.12 1098.00 249.12 c +1103.57 249.12 1108.08 253.63 1108.08 259.20 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1113.84 259.20 m 1113.84 267.95 1106.75 275.04 1098.00 275.04 c +1089.25 275.04 1082.16 267.95 1082.16 259.20 c +1082.16 250.45 1089.25 243.36 1098.00 243.36 c +1106.75 243.36 1113.84 250.45 1113.84 259.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1128.96 256.91 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1119.56 260.51 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1112.400 259.200 m +1126.800 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1083.60 278.51 Td +(MH3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1158.48 259.20 m 1158.48 264.77 1153.97 269.28 1148.40 269.28 c +1142.83 269.28 1138.32 264.77 1138.32 259.20 c +1138.32 253.63 1142.83 249.12 1148.40 249.12 c +1153.97 249.12 1158.48 253.63 1158.48 259.20 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1164.24 259.20 m 1164.24 267.95 1157.15 275.04 1148.40 275.04 c +1139.65 275.04 1132.56 267.95 1132.56 259.20 c +1132.56 250.45 1139.65 243.36 1148.40 243.36 c +1157.15 243.36 1164.24 250.45 1164.24 259.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1179.36 256.91 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1169.96 260.51 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 259.200 m +1177.200 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1134.00 278.51 Td +(MH4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1116.000 295.200 m +1116.000 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1108.800 288.000 m +1123.200 288.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1115.280 281.520 m +1116.720 281.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1113.120 283.680 m +1118.880 283.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1110.960 285.840 m +1121.040 285.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1108.73 274.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1116.000 302.400 m +1112.400 302.400 l +S +1116.000 295.200 m +1116.000 302.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1116.000 302.400 m +1112.400 302.400 l +S +1116.000 295.200 m +1116.000 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 302.400 m +1162.800 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1155.600 295.200 m +1170.000 295.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1162.080 288.720 m +1163.520 288.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1159.920 290.880 m +1165.680 290.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1157.760 293.040 m +1167.840 293.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1155.53 282.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 302.400 m +1162.800 302.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 302.400 m +1162.800 302.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1112.400 259.200 m +1112.400 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1105.200 252.000 m +1119.600 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1111.680 245.520 m +1113.120 245.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1109.520 247.680 m +1115.280 247.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1107.360 249.840 m +1117.440 249.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1105.13 238.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1112.400 259.200 m +1112.400 259.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1112.400 259.200 m +1112.400 259.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1162.800 259.200 m +1162.800 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1155.600 252.000 m +1170.000 252.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1162.080 245.520 m +1163.520 245.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1159.920 247.680 m +1165.680 247.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1157.760 249.840 m +1167.840 249.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1155.53 238.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 259.200 m +1162.800 259.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1162.800 259.200 m +1162.800 259.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 496.15 712.80 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +496.800 720.000 m +496.800 712.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 496.15 694.76 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +496.800 691.200 m +496.800 698.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 488.95 712.80 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +489.600 720.000 m +489.600 712.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 488.95 694.76 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +489.600 691.200 m +489.600 698.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +496.800 691.200 m +496.800 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 698.400 m +489.600 702.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 712.800 m +489.600 708.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +490.32 703.44 m 490.32 703.84 490.00 704.16 489.60 704.16 c +489.20 704.16 488.88 703.84 488.88 703.44 c +488.88 703.04 489.20 702.72 489.60 702.72 c +490.00 702.72 490.32 703.04 490.32 703.44 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +490.32 707.76 m 490.32 708.16 490.00 708.48 489.60 708.48 c +489.20 708.48 488.88 708.16 488.88 707.76 c +488.88 707.36 489.20 707.04 489.60 707.04 c +490.00 707.04 490.32 707.36 490.32 707.76 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +487.440 704.160 m +488.880 708.480 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +500.40 706.48 Td +(SW9) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +489.600 687.600 m +489.600 691.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +489.600 687.600 m +489.600 691.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 571.75 709.20 Tm +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 716.400 m +572.400 709.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 571.75 691.16 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 687.600 m +572.400 694.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 564.55 709.20 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.200 716.400 m +565.200 709.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 564.55 691.16 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.200 687.600 m +565.200 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +572.400 687.600 m +572.400 716.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +565.200 694.800 m +565.200 699.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +565.200 709.200 m +565.200 704.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.92 699.84 m 565.92 700.24 565.60 700.56 565.20 700.56 c +564.80 700.56 564.48 700.24 564.48 699.84 c +564.48 699.44 564.80 699.12 565.20 699.12 c +565.60 699.12 565.92 699.44 565.92 699.84 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +565.92 704.16 m 565.92 704.56 565.60 704.88 565.20 704.88 c +564.80 704.88 564.48 704.56 564.48 704.16 c +564.48 703.76 564.80 703.44 565.20 703.44 c +565.60 703.44 565.92 703.76 565.92 704.16 c +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +563.040 700.560 m +564.480 704.880 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +576.00 702.88 Td +(SW10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +496.800 720.000 m +504.000 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +504.000 712.800 m +504.000 727.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +510.480 719.280 m +510.480 720.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +508.320 717.120 m +508.320 722.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +506.160 714.960 m +506.160 725.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 517.09 712.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +496.800 720.000 m +496.800 720.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +496.800 720.000 m +496.800 720.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +496.800 691.200 m +504.000 691.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +504.000 684.000 m +504.000 698.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +510.480 690.480 m +510.480 691.920 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +508.320 688.320 m +508.320 694.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +506.160 686.160 m +506.160 696.240 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 517.09 683.93 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +496.800 691.200 m +496.800 691.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +496.800 691.200 m +496.800 691.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 716.400 m +579.600 716.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 709.200 m +579.600 723.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.080 715.680 m +586.080 717.120 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +583.920 713.520 m +583.920 719.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +581.760 711.360 m +581.760 721.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 592.69 709.13 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +572.400 716.400 m +572.400 716.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +572.400 716.400 m +572.400 716.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.400 687.600 m +579.600 687.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 680.400 m +579.600 694.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.080 686.880 m +586.080 688.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +583.920 684.720 m +583.920 690.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +581.760 682.560 m +581.760 692.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 592.69 680.33 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +572.400 687.600 m +572.400 687.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +572.400 687.600 m +572.400 687.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +579.60 104.40 7.20 -14.40 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +572.40 133.20 28.80 -28.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +594.000 126.720 m +594.000 128.880 l +594.720 127.440 l +593.280 127.440 l +594.000 128.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.800 126.720 m +586.800 128.880 l +587.520 127.440 l +586.080 127.440 l +586.800 128.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 126.720 m +579.600 128.880 l +580.320 127.440 l +578.880 127.440 l +579.600 128.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 123.840 m +579.600 125.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 120.240 m +579.600 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 115.920 m +579.600 118.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +579.600 111.600 m +579.600 114.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +582.480 111.600 m +580.320 111.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.800 113.040 m +586.800 111.600 l +583.920 111.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.800 115.920 m +586.800 114.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +586.800 118.800 m +586.800 117.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +594.000 128.880 m +594.000 118.800 l +586.800 118.800 l +586.800 128.880 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 577.57 134.58 Tm +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +579.600 140.400 m +579.600 133.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +576.720 143.280 m +582.480 137.520 l +576.720 137.520 m +582.480 143.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 584.77 134.58 Tm +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +586.800 140.400 m +586.800 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 591.97 134.58 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +594.000 140.400 m +594.000 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +572.40 80.51 Td +(SW11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +568.80 73.31 Td +(MK-12D13G4-B) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +586.800 151.200 m +586.800 158.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +594.000 158.400 m +579.600 158.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +587.520 164.880 m +586.080 164.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +589.680 162.720 m +583.920 162.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +591.840 160.560 m +581.760 160.560 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +579.53 166.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +586.800 151.200 m +586.800 140.400 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +586.800 151.200 m +586.800 140.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +507.60 141.12 6.48 -8.64 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +507.60 129.60 6.48 -14.40 re +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +507.60 112.32 6.48 -8.64 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 136.800 m +522.000 136.800 l +522.000 117.360 l +514.080 117.360 l +518.400 116.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 117.360 m +518.400 118.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 136.800 m +518.400 136.080 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 136.800 m +518.400 137.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 127.440 m +525.600 127.440 l +525.600 108.000 l +514.080 108.000 l +518.400 107.280 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 108.000 m +518.400 108.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 127.440 m +518.400 126.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +514.080 127.440 m +518.400 128.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +498.98 138.83 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +493.200 136.800 m +507.600 136.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +498.98 124.43 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +493.200 122.400 m +507.600 122.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +498.98 110.03 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +493.200 108.000 m +507.600 108.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +498.98 102.83 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +493.200 100.800 m +507.600 100.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +498.98 146.03 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +493.200 144.000 m +507.600 144.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +507.600 144.000 m +529.200 144.000 l +529.200 100.800 l +507.600 100.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +507.60 148.91 Td +(SW12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +486.00 91.31 Td +(SS-12D11G5R) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +511.200 162.000 m +518.400 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +518.400 154.800 m +518.400 169.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +524.880 161.280 m +524.880 162.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +522.720 159.120 m +522.720 164.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +520.560 156.960 m +520.560 167.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 531.49 154.73 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 79.200 m +482.400 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +475.200 72.000 m +489.600 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +481.680 65.520 m +483.120 65.520 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +479.520 67.680 m +485.280 67.680 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +477.360 69.840 m +487.440 69.840 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +475.13 58.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 100.800 m +493.200 100.800 l +S +482.400 79.200 m +482.400 100.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 100.800 m +493.200 100.800 l +S +482.400 79.200 m +482.400 100.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +493.200 162.000 m +511.200 162.000 l +S +493.200 144.000 m +493.200 162.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +493.200 162.000 m +511.200 162.000 l +S +493.200 144.000 m +493.200 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +426.960 55.440 m +415.440 55.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +426.960 52.560 m +415.440 52.560 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +421.200 64.800 m +421.200 57.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +421.200 43.200 m +421.200 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +421.200 57.600 m +421.200 55.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +421.200 52.560 m +421.200 50.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +424.080 61.200 m +424.080 58.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +425.520 59.760 m +422.640 59.760 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +428.40 44.51 Td +(C39) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +428.40 37.31 Td +(220uF) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +457.20 162.00 14.40 -21.60 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +469.08 144.00 m 469.08 144.60 468.60 145.08 468.00 145.08 c +467.40 145.08 466.92 144.60 466.92 144.00 c +466.92 143.40 467.40 142.92 468.00 142.92 c +468.60 142.92 469.08 143.40 469.08 144.00 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +465.30 144.65 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +471.96 148.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +478.800 147.600 m +471.600 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +465.30 151.85 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +471.96 155.45 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +478.800 154.800 m +471.600 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +457.20 163.31 Td +(U25) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +392.40 159.71 Td +(S2B-XH-A-BK\(LF\)\(SN\)) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +471.600 136.800 m +457.200 136.800 l +S +471.600 136.800 m +471.600 122.400 l +S +493.200 122.400 m +471.600 122.400 l +S +471.600 122.400 m +471.600 104.400 l +S +457.200 104.400 m +471.600 104.400 l +S +471.600 104.400 m +471.600 64.800 l +S +457.200 64.800 m +471.600 64.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +471.600 136.800 m +457.200 136.800 l +S +471.600 136.800 m +471.600 122.400 l +S +493.200 122.400 m +471.600 122.400 l +S +471.600 122.400 m +471.600 104.400 l +S +457.200 104.400 m +471.600 104.400 l +S +471.600 104.400 m +471.600 64.800 l +S +457.200 64.800 m +471.600 64.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +478.800 136.800 m +478.800 147.600 l +S +493.200 136.800 m +478.800 136.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +478.800 136.800 m +478.800 147.600 l +S +493.200 136.800 m +478.800 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +482.400 154.800 m +482.400 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +489.600 162.000 m +475.200 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +483.120 168.480 m +481.680 168.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +485.280 166.320 m +479.520 166.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +487.440 164.160 m +477.360 164.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +489.53 166.91 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 154.800 m +478.800 154.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +482.400 154.800 m +478.800 154.800 l +S +0.00 0.00 1.00 RG +0.72 w +390.960 147.600 m +393.840 147.600 l +S +392.400 149.040 m +392.400 146.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +392.40 148.91 Td +(VBUSINESP) Tj +ET +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +1083.60 222.22 Td +(Mounting Holes) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +1072.80 338.40 118.80 -126.00 re +S +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +558.00 176.40 68.40 -147.60 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +561.60 56.62 Td +(Calibration) Tj +T* (Switch) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +259.200 410.400 m +259.200 417.600 l +S +1 J +1 j +0.72 w +0.60 G +[] 0 d +259.200 439.200 m +259.200 432.000 l +S +0.60 G +0.00 w +[] 0 d +259.920 432.000 m +256.320 428.400 l +S +262.080 430.560 m +256.320 424.800 l +S +262.080 426.960 m +256.320 421.200 l +S +262.080 423.360 m +256.320 417.600 l +S +262.080 419.760 m +259.920 417.600 l +S +259.920 417.600 m +256.320 421.200 l +S +262.080 419.040 m +256.320 424.800 l +S +262.080 422.640 m +256.320 428.400 l +S +256.320 432.000 m +262.080 426.240 l +S +259.920 432.000 m +262.080 429.840 l +S +2 J +0 j +72 M +0.72 w +0.60 G +0.60 g +[] 0 d +256.32 432.00 5.76 -14.40 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +266.40 426.11 Td +(R19) Tj +ET +7.20 w +BT +7.20 TL +0.600 g +266.40 418.91 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +0.60 G +0.00 w +[] 0 d +43.200 162.000 m +39.600 158.400 l +S +46.800 162.000 m +39.600 154.800 l +S +50.400 162.000 m +39.600 151.200 l +S +54.000 162.000 m +39.600 147.600 l +S +54.000 158.400 m +39.600 144.000 l +S +54.000 154.800 m +39.600 140.400 l +S +54.000 151.200 m +39.600 136.800 l +S +54.000 147.600 m +39.600 133.200 l +S +54.000 144.000 m +39.600 129.600 l +S +54.000 140.400 m +39.600 126.000 l +S +54.000 136.800 m +39.600 122.400 l +S +54.000 133.200 m +39.600 118.800 l +S +54.000 129.600 m +39.600 115.200 l +S +54.000 126.000 m +39.600 111.600 l +S +54.000 122.400 m +39.600 108.000 l +S +54.000 118.800 m +39.600 104.400 l +S +54.000 115.200 m +39.600 100.800 l +S +54.000 111.600 m +39.600 97.200 l +S +54.000 108.000 m +43.200 97.200 l +S +54.000 104.400 m +46.800 97.200 l +S +54.000 100.800 m +50.400 97.200 l +S +43.200 97.200 m +39.600 100.800 l +S +46.800 97.200 m +39.600 104.400 l +S +50.400 97.200 m +39.600 108.000 l +S +54.000 97.200 m +39.600 111.600 l +S +54.000 100.800 m +39.600 115.200 l +S +54.000 104.400 m +39.600 118.800 l +S +54.000 108.000 m +39.600 122.400 l +S +54.000 111.600 m +39.600 126.000 l +S +54.000 115.200 m +39.600 129.600 l +S +54.000 118.800 m +39.600 133.200 l +S +54.000 122.400 m +39.600 136.800 l +S +54.000 126.000 m +39.600 140.400 l +S +54.000 129.600 m +39.600 144.000 l +S +54.000 133.200 m +39.600 147.600 l +S +54.000 136.800 m +39.600 151.200 l +S +54.000 140.400 m +39.600 154.800 l +S +54.000 144.000 m +39.600 158.400 l +S +39.600 162.000 m +54.000 147.600 l +S +43.200 162.000 m +54.000 151.200 l +S +46.800 162.000 m +54.000 154.800 l +S +50.400 162.000 m +54.000 158.400 l +S +2 J +0 j +72 M +0.72 w +0.60 G +0.60 g +[] 0 d +39.60 162.00 14.40 -64.80 re +S +0.60 G +0.00 w +[] 0 d +51.375 100.335 m +50.865 99.825 l +S +50.865 101.775 m +51.375 101.265 l +S +1 J +1 j +0.72 w +0.60 G +0.60 g +[] 0 d +51.48 100.80 m 51.48 101.40 51.00 101.88 50.40 101.88 c +49.80 101.88 49.32 101.40 49.32 100.80 c +49.32 100.20 49.80 99.72 50.40 99.72 c +51.00 99.72 51.48 100.20 51.48 100.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 101.45 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 105.05 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 104.400 m +54.000 104.400 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +58.320 107.280 m +64.080 101.520 l +58.320 101.520 m +64.080 107.280 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 108.65 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 112.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 111.600 m +54.000 111.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 115.85 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 119.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 118.800 m +54.000 118.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 123.05 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 126.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 126.000 m +54.000 126.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 130.25 Td +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 133.85 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 133.200 m +54.000 133.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 137.45 Td +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 141.05 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 140.400 m +54.000 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 144.65 Td +(7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 148.25 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 147.600 m +54.000 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +47.70 151.85 Td +(8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +54.36 155.45 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +61.200 154.800 m +54.000 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +39.60 163.31 Td +(H10) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +39.60 91.31 Td +(PZ254V-11-08P) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +831.60 320.40 28.80 -208.80 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 295.85 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 299.45 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 298.800 m +831.600 298.800 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +814.320 301.680 m +820.080 295.920 l +814.320 295.920 m +820.080 301.680 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 288.65 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 292.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 291.600 m +831.600 291.600 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +814.320 294.480 m +820.080 288.720 l +814.320 288.720 m +820.080 294.480 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 281.45 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 285.05 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 284.400 m +831.600 284.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 274.25 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 277.85 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 277.200 m +831.600 277.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 267.05 Td +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 270.65 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 270.000 m +831.600 270.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 259.85 Td +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 263.45 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 262.800 m +831.600 262.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 252.65 Td +(7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 256.25 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 255.600 m +831.600 255.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 245.45 Td +(8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 249.05 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 248.400 m +831.600 248.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 238.25 Td +(9) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +824.00 241.85 Td +(9) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 241.200 m +831.600 241.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 231.05 Td +(10) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 234.65 Td +(10) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 234.000 m +831.600 234.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 223.85 Td +(11) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 227.45 Td +(11) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 226.800 m +831.600 226.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 216.65 Td +(12) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 220.25 Td +(12) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 219.600 m +831.600 219.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 209.45 Td +(13) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 213.05 Td +(13) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 212.400 m +831.600 212.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 202.25 Td +(14) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 205.85 Td +(14) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 205.200 m +831.600 205.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 195.05 Td +(15) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 198.65 Td +(15) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 198.000 m +831.600 198.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 187.85 Td +(16) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 191.45 Td +(16) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 190.800 m +831.600 190.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 180.65 Td +(17) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 184.25 Td +(17) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 183.600 m +831.600 183.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 173.45 Td +(18) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 177.05 Td +(18) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 176.400 m +831.600 176.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 166.25 Td +(19) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 169.85 Td +(19) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 169.200 m +831.600 169.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 159.05 Td +(20) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 162.65 Td +(20) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 162.000 m +831.600 162.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 151.85 Td +(21) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 155.45 Td +(21) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 154.800 m +831.600 154.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 144.65 Td +(22) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 148.25 Td +(22) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 147.600 m +831.600 147.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 137.45 Td +(23) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 141.05 Td +(23) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 140.400 m +831.600 140.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 130.25 Td +(24) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 133.85 Td +(24) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 133.200 m +831.600 133.200 l +S +1 J +1 j +0.72 w +0.20 0.80 0.20 RG +[] 0 d +814.320 136.080 m +820.080 130.320 l +814.320 130.320 m +820.080 136.080 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 310.25 Td +(25) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 313.85 Td +(25) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 313.200 m +831.600 313.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +834.26 115.85 Td +(26) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +820.36 119.45 Td +(26) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +817.200 118.800 m +831.600 118.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +831.60 321.28 Td +(FPC3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +802.80 102.11 Td +(AFC07-S24FCA-00) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +743.760 254.160 m +743.760 242.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +746.640 254.160 m +746.640 242.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +734.400 248.400 m +741.600 248.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 248.400 m +748.800 248.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +741.600 248.400 m +743.760 248.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +746.640 248.400 m +748.800 248.400 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +741.60 256.48 Td +(C40) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +741.60 235.31 Td +(15pF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +746.640 205.200 m +748.800 205.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +741.600 205.200 m +743.760 205.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 205.200 m +748.800 205.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +734.400 205.200 m +741.600 205.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +746.640 210.960 m +746.640 199.440 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +743.760 210.960 m +743.760 199.440 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +741.60 213.71 Td +(C41) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +738.00 192.11 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +770.400 205.200 m +770.400 208.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +766.800 212.400 m +774.000 212.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +770.400 212.400 m +770.400 208.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +756.40 213.71 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +813.600 313.200 m +806.400 313.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +806.400 320.400 m +806.400 306.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +799.920 313.920 m +799.920 312.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +802.080 316.080 m +802.080 310.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +804.240 318.240 m +804.240 308.160 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 797.89 305.93 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +813.600 313.200 m +817.200 313.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +813.600 313.200 m +817.200 313.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +651.60 174.11 Td +(CAMRST) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 162.000 m +666.000 151.200 l +S +651.600 162.000 m +666.000 162.000 l +S +651.600 162.000 m +651.600 172.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +651.60 174.11 Td +(CAMRST) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 162.000 m +666.000 151.200 l +S +651.600 162.000 m +666.000 162.000 l +S +651.600 162.000 m +651.600 172.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +666.000 141.840 m +666.000 144.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +666.000 136.800 m +666.000 138.960 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 151.200 m +666.000 144.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 129.600 m +666.000 136.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +660.240 141.840 m +671.760 141.840 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +660.240 138.960 m +671.760 138.960 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +673.20 141.71 Td +(C42) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +676.80 134.51 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +694.800 162.000 m +687.600 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 162.000 m +673.200 162.000 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +673.20 164.88 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +673.20 166.91 Td +(R30) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +673.20 152.51 Td +/F2 6.545454545454544 Tf +(4.7k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 165.600 m +698.400 169.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +694.800 172.800 m +702.000 172.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.400 172.800 m +698.400 169.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +684.40 174.11 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 165.600 m +698.400 162.000 l +S +698.400 162.000 m +694.800 162.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 165.600 m +698.400 162.000 l +S +698.400 162.000 m +694.800 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 129.600 m +658.800 129.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +658.800 136.800 m +658.800 122.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +652.320 130.320 m +652.320 128.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +654.480 132.480 m +654.480 126.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +656.640 134.640 m +656.640 124.560 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +0.00 1.00 -1.00 0.00 650.29 122.33 Tm +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 129.600 m +666.000 129.600 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 129.600 m +666.000 129.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +766.800 154.800 m +766.800 158.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +763.200 162.000 m +770.400 162.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +766.800 162.000 m +766.800 158.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +760.07 163.31 Td +(2.8V) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +763.200 187.200 m +763.200 190.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +759.600 194.400 m +766.800 194.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +763.200 194.400 m +763.200 190.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +756.47 195.71 Td +(1.2V) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +694.800 223.200 m +687.600 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 223.200 m +673.200 223.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +673.20 226.08 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +673.20 228.11 Td +(R31) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +673.20 213.71 Td +/F2 6.545454545454544 Tf +(4.7k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +694.800 201.600 m +687.600 201.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +666.000 201.600 m +673.200 201.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +673.20 204.48 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +673.20 206.51 Td +(R32) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +673.20 192.11 Td +/F2 6.545454545454544 Tf +(4.7k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +694.800 223.200 m +702.000 223.200 l +S +702.000 223.200 m +702.000 201.600 l +S +702.000 201.600 m +694.800 201.600 l +S +702.000 223.200 m +716.400 223.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +694.800 223.200 m +702.000 223.200 l +S +702.000 223.200 m +702.000 201.600 l +S +702.000 201.600 m +694.800 201.600 l +S +702.000 223.200 m +716.400 223.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +716.400 223.200 m +716.400 226.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +712.800 230.400 m +720.000 230.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +716.400 230.400 m +716.400 226.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +695.20 231.71 Td +(MAXVDD) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +640.80 224.51 Td +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 223.200 m +640.800 223.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +640.80 224.51 Td +(CAMSIOC) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 223.200 m +640.800 223.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +640.80 202.91 Td +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 201.600 m +640.800 201.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +640.80 202.91 Td +(CAMSIOD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +666.000 201.600 m +640.800 201.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +679.46 303.05 Td +(VIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +672.80 306.65 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +669.600 306.000 m +676.800 306.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +699.15 303.05 Td +(VOUT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +720.36 306.65 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +727.200 306.000 m +720.000 306.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 699.97 285.69 Tm +(VSS) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +0.00 1.00 -1.00 0.00 696.37 279.02 Tm +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 277.200 m +698.400 284.400 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +676.80 313.20 43.20 -28.80 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +676.80 285.71 Td +(U26) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +673.20 314.51 Td +(XC6206P282MR) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +651.600 313.200 m +651.600 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +648.000 320.400 m +655.200 320.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +651.600 320.400 m +651.600 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +637.60 321.71 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +651.600 306.000 m +651.600 313.200 l +S +669.600 306.000 m +651.600 306.000 l +S +651.600 291.600 m +651.600 306.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +651.600 306.000 m +651.600 313.200 l +S +669.600 306.000 m +651.600 306.000 l +S +651.600 291.600 m +651.600 306.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +676.800 64.800 m +676.800 68.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +673.200 72.000 m +680.400 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +676.800 72.000 m +676.800 68.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +662.80 76.91 Td +(MAXVDD) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +763.200 64.800 m +763.200 61.200 l +S +698.400 61.200 m +763.200 61.200 l +S +698.400 61.200 m +676.800 61.200 l +S +676.800 64.800 m +676.800 61.200 l +S +698.400 68.400 m +698.400 61.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +763.200 64.800 m +763.200 61.200 l +S +698.400 61.200 m +763.200 61.200 l +S +698.400 61.200 m +676.800 61.200 l +S +676.800 64.800 m +676.800 61.200 l +S +698.400 68.400 m +698.400 61.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +712.800 72.000 m +712.800 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +709.200 79.200 m +716.400 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +712.800 79.200 m +712.800 75.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +706.07 80.51 Td +(1.2V) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +748.800 72.000 m +763.200 72.000 l +S +727.200 72.000 m +748.800 72.000 l +S +727.200 72.000 m +712.800 72.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +748.800 72.000 m +763.200 72.000 l +S +727.200 72.000 m +748.800 72.000 l +S +727.200 72.000 m +712.800 72.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +658.800 86.400 m +658.800 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +651.600 79.200 m +666.000 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +658.080 72.720 m +659.520 72.720 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +655.920 74.880 m +661.680 74.880 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +653.760 77.040 m +663.840 77.040 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +651.53 66.11 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +658.800 86.400 m +658.800 100.800 l +S +698.400 100.800 m +658.800 100.800 l +S +698.400 100.800 m +727.200 100.800 l +S +727.200 100.800 m +727.200 93.600 l +S +727.200 100.800 m +748.800 100.800 l +S +748.800 100.800 m +763.200 100.800 l +S +763.200 79.200 m +763.200 100.800 l +S +748.800 93.600 m +748.800 100.800 l +S +698.400 90.000 m +698.400 100.800 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +658.800 86.400 m +658.800 100.800 l +S +698.400 100.800 m +658.800 100.800 l +S +698.400 100.800 m +727.200 100.800 l +S +727.200 100.800 m +727.200 93.600 l +S +727.200 100.800 m +748.800 100.800 l +S +748.800 100.800 m +763.200 100.800 l +S +763.200 79.200 m +763.200 100.800 l +S +748.800 93.600 m +748.800 100.800 l +S +698.400 90.000 m +698.400 100.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 270.000 m +698.400 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +691.200 262.800 m +705.600 262.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +697.680 256.320 m +699.120 256.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +695.520 258.480 m +701.280 258.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +693.360 260.640 m +703.440 260.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +691.13 249.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 270.000 m +698.400 277.200 l +S +698.400 270.000 m +651.600 270.000 l +S +734.400 270.000 m +698.400 270.000 l +S +734.400 270.000 m +756.000 270.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +698.400 270.000 m +698.400 277.200 l +S +698.400 270.000 m +651.600 270.000 l +S +734.400 270.000 m +698.400 270.000 l +S +734.400 270.000 m +756.000 270.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +770.400 313.200 m +770.400 316.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +766.800 320.400 m +774.000 320.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +770.400 320.400 m +770.400 316.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +763.67 321.71 Td +(2.8V) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +770.400 313.200 m +770.400 306.000 l +S +756.000 306.000 m +770.400 306.000 l +S +756.000 306.000 m +734.400 306.000 l +S +734.400 306.000 m +734.400 291.600 l +S +727.200 306.000 m +734.400 306.000 l +S +756.000 291.600 m +756.000 306.000 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +770.400 313.200 m +770.400 306.000 l +S +756.000 306.000 m +770.400 306.000 l +S +756.000 306.000 m +734.400 306.000 l +S +734.400 306.000 m +734.400 291.600 l +S +727.200 306.000 m +734.400 306.000 l +S +756.000 291.600 m +756.000 306.000 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +756.000 282.240 m +756.000 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +756.000 277.200 m +756.000 279.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 291.600 m +756.000 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +756.000 270.000 m +756.000 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +750.240 282.240 m +761.760 282.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +750.240 279.360 m +761.760 279.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +741.60 285.71 Td +(C43) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +738.00 271.31 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +728.640 279.360 m +740.160 279.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +728.640 282.240 m +740.160 282.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +734.400 270.000 m +734.400 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +734.400 291.600 m +734.400 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +734.400 277.200 m +734.400 279.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +734.400 282.240 m +734.400 284.400 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +727.20 274.48 Td +(C44) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +720.00 285.71 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +651.600 282.240 m +651.600 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +651.600 277.200 m +651.600 279.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +651.600 291.600 m +651.600 284.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +651.600 270.000 m +651.600 277.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +645.840 282.240 m +657.360 282.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +645.840 279.360 m +657.360 279.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +658.80 282.11 Td +(C45) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +662.40 274.91 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +748.800 84.240 m +748.800 86.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +748.800 79.200 m +748.800 81.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +748.800 93.600 m +748.800 86.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +748.800 72.000 m +748.800 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +743.040 84.240 m +754.560 84.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +743.040 81.360 m +754.560 81.360 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +741.60 76.91 Td +(C46) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +738.00 87.71 Td +(100nF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +721.440 81.360 m +732.960 81.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +721.440 84.240 m +732.960 84.240 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +727.200 72.000 m +727.200 79.200 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +727.200 93.600 m +727.200 86.400 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +727.200 79.200 m +727.200 81.360 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +727.200 84.240 m +727.200 86.400 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +730.80 76.48 Td +(C47) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +716.40 91.31 Td +(10uF) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +692.640 77.760 m +704.160 77.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +692.640 80.640 m +704.160 80.640 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 68.400 m +698.400 75.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +698.400 90.000 m +698.400 82.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.400 75.600 m +698.400 77.760 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +698.400 80.640 m +698.400 82.800 l +S +7.20 w +BT +/F2 4.418181818181818 Tf +4.86 TL +0.000 0.000 0.502 rg +702.00 72.88 Td +(C48) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +680.40 84.11 Td +(10uF) Tj +ET +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +770.40 86.40 28.80 -28.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +775.08 82.80 m 775.08 83.40 774.60 83.88 774.00 83.88 c +773.40 83.88 772.92 83.40 772.92 82.80 c +772.92 82.20 773.40 81.72 774.00 81.72 c +774.60 81.72 775.08 82.20 775.08 82.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +773.06 76.25 Td +(GND) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +766.40 79.85 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +763.200 79.200 m +770.400 79.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +773.06 69.05 Td +(VOUT) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +766.40 72.65 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +763.200 72.000 m +770.400 72.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +773.06 61.85 Td +(VIN) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +766.40 65.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +763.200 64.800 m +770.400 64.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +770.40 87.71 Td +(U28) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +770.40 51.71 Td +(SSP7615-12MR) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +730.800 183.600 m +738.000 183.600 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +759.600 183.600 m +752.400 183.600 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +738.00 186.48 14.40 -5.76 re +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +734.40 166.91 Td +(R33) Tj +ET +7.20 w +BT +7.20 TL +0.000 0.000 1.000 rg +738.00 174.11 Td +/F2 6.545454545454544 Tf +(1k) Tj +/F3 6.545454545454544 Tf +<03a9> Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 486.000 m +1314.000 478.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1306.800 478.800 m +1321.200 478.800 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1313.280 472.320 m +1314.720 472.320 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1311.120 474.480 m +1316.880 474.480 l +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +0.00 g +[] 0 d +1308.960 476.640 m +1319.040 476.640 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1306.73 465.71 Td +(GND) Tj +ET +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 486.000 m +1314.000 493.200 l +S +1314.000 500.400 m +1314.000 493.200 l +S +1 J +1 j +0.72 w +0.00 0.53 0.00 RG +0.00 g +[] 0 d +1314.000 486.000 m +1314.000 493.200 l +S +1314.000 500.400 m +1314.000 493.200 l +S +2 J +0 j +72 M +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1321.20 550.80 14.40 -64.80 re +S +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1325.88 547.20 m 1325.88 547.80 1325.40 548.28 1324.80 548.28 c +1324.20 548.28 1323.72 547.80 1323.72 547.20 c +1323.72 546.60 1324.20 546.12 1324.80 546.12 c +1325.40 546.12 1325.88 546.60 1325.88 547.20 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 540.65 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 544.25 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 543.600 m +1321.200 543.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 533.45 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 537.05 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 536.400 m +1321.200 536.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 526.25 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 529.85 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 529.200 m +1321.200 529.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 519.05 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 522.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 522.000 m +1321.200 522.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 511.85 Td +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 515.45 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 514.800 m +1321.200 514.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 504.65 Td +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 508.25 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 507.600 m +1321.200 507.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 497.45 Td +(7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 501.05 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 500.400 m +1321.200 500.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1323.86 490.25 Td +(8) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 g +1317.20 493.85 Td +(8) Tj +ET +1 J +1 j +0.72 w +0.63 0.00 0.00 RG +[] 0 d +1314.000 493.200 m +1321.200 493.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 0.502 rg +1321.20 552.11 Td +(CN4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.000 0.000 1.000 rg +0.00 1.00 -1.00 0.00 1345.09 496.80 Tm +(HC-1.25-6PWT) Tj +ET +2 J +0 j +72 M +0.72 w +0.00 G +[] 0 d +633.60 338.40 234.00 -309.60 re +S +7.20 w +BT +/F2 13.090909090909088 Tf +14.40 TL +0.000 g +651.60 38.62 Td +(Main Camera) Tj +ET +0.60 G +0.00 w +[] 0 d +1220.400 748.800 m +1216.800 745.200 l +S +1224.000 748.800 m +1216.800 741.600 l +S +1227.600 748.800 m +1216.800 738.000 l +S +1231.200 748.800 m +1216.800 734.400 l +S +1231.200 745.200 m +1216.800 730.800 l +S +1231.200 741.600 m +1216.800 727.200 l +S +1231.200 738.000 m +1216.800 723.600 l +S +1231.200 734.400 m +1216.800 720.000 l +S +1231.200 730.800 m +1216.800 716.400 l +S +1231.200 727.200 m +1216.800 712.800 l +S +1231.200 723.600 m +1216.800 709.200 l +S +1231.200 720.000 m +1216.800 705.600 l +S +1231.200 716.400 m +1216.800 702.000 l +S +1231.200 712.800 m +1216.800 698.400 l +S +1231.200 709.200 m +1216.800 694.800 l +S +1231.200 705.600 m +1216.800 691.200 l +S +1231.200 702.000 m +1220.400 691.200 l +S +1231.200 698.400 m +1224.000 691.200 l +S +1231.200 694.800 m +1227.600 691.200 l +S +1220.400 691.200 m +1216.800 694.800 l +S +1224.000 691.200 m +1216.800 698.400 l +S +1227.600 691.200 m +1216.800 702.000 l +S +1231.200 691.200 m +1216.800 705.600 l +S +1231.200 694.800 m +1216.800 709.200 l +S +1231.200 698.400 m +1216.800 712.800 l +S +1231.200 702.000 m +1216.800 716.400 l +S +1231.200 705.600 m +1216.800 720.000 l +S +1231.200 709.200 m +1216.800 723.600 l +S +1231.200 712.800 m +1216.800 727.200 l +S +1231.200 716.400 m +1216.800 730.800 l +S +1231.200 720.000 m +1216.800 734.400 l +S +1231.200 723.600 m +1216.800 738.000 l +S +1231.200 727.200 m +1216.800 741.600 l +S +1231.200 730.800 m +1216.800 745.200 l +S +1216.800 748.800 m +1231.200 734.400 l +S +1220.400 748.800 m +1231.200 738.000 l +S +1224.000 748.800 m +1231.200 741.600 l +S +1227.600 748.800 m +1231.200 745.200 l +S +2 J +0 j +72 M +0.72 w +0.60 G +0.60 g +[] 0 d +1216.80 748.80 14.40 -57.60 re +S +0.60 G +0.00 w +[] 0 d +1228.575 694.335 m +1228.065 693.825 l +S +1228.575 695.265 m +1228.065 695.775 l +S +1 J +1 j +0.72 w +0.60 G +0.60 g +[] 0 d +1228.68 694.80 m 1228.68 695.40 1228.20 695.88 1227.60 695.88 c +1227.00 695.88 1226.52 695.40 1226.52 694.80 c +1226.52 694.20 1227.00 693.72 1227.60 693.72 c +1228.20 693.72 1228.68 694.20 1228.68 694.80 c +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 695.45 Td +(1) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 699.05 Td +(1) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 698.400 m +1231.200 698.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 702.65 Td +(2) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 706.25 Td +(2) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 705.600 m +1231.200 705.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 709.85 Td +(3) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 713.45 Td +(3) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 712.800 m +1231.200 712.800 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 717.05 Td +(4) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 720.65 Td +(4) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 720.000 m +1231.200 720.000 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 724.25 Td +(5) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 727.85 Td +(5) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 727.200 m +1231.200 727.200 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 731.45 Td +(6) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 735.05 Td +(6) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 734.400 m +1231.200 734.400 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1224.90 738.65 Td +(7) Tj +ET +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1231.56 742.25 Td +(7) Tj +ET +1 J +1 j +0.72 w +0.60 G +[] 0 d +1238.400 741.600 m +1231.200 741.600 l +S +7.20 w +BT +/F2 6.545454545454544 Tf +7.20 TL +0.600 g +1216.80 750.11 Td +(U20) Tj +ET +0.80 0.00 0.00 rg +1031.40 601.20 m 1031.40 602.19 1030.59 603.00 1029.60 603.00 c +1028.61 603.00 1027.80 602.19 1027.80 601.20 c +1027.80 600.21 1028.61 599.40 1029.60 599.40 c +1030.59 599.40 1031.40 600.21 1031.40 601.20 c +f +0.80 0.00 0.00 rg +1035.00 601.20 m 1035.00 602.19 1034.19 603.00 1033.20 603.00 c +1032.21 603.00 1031.40 602.19 1031.40 601.20 c +1031.40 600.21 1032.21 599.40 1033.20 599.40 c +1034.19 599.40 1035.00 600.21 1035.00 601.20 c +f +0.80 0.00 0.00 rg +1089.00 565.20 m 1089.00 566.19 1088.19 567.00 1087.20 567.00 c +1086.21 567.00 1085.40 566.19 1085.40 565.20 c +1085.40 564.21 1086.21 563.40 1087.20 563.40 c +1088.19 563.40 1089.00 564.21 1089.00 565.20 c +f +0.80 0.00 0.00 rg +1045.80 565.20 m 1045.80 566.19 1044.99 567.00 1044.00 567.00 c +1043.01 567.00 1042.20 566.19 1042.20 565.20 c +1042.20 564.21 1043.01 563.40 1044.00 563.40 c +1044.99 563.40 1045.80 564.21 1045.80 565.20 c +f +0.80 0.00 0.00 rg +1135.80 601.20 m 1135.80 602.19 1134.99 603.00 1134.00 603.00 c +1133.01 603.00 1132.20 602.19 1132.20 601.20 c +1132.20 600.21 1133.01 599.40 1134.00 599.40 c +1134.99 599.40 1135.80 600.21 1135.80 601.20 c +f +0.80 0.00 0.00 rg +1143.00 601.20 m 1143.00 602.19 1142.19 603.00 1141.20 603.00 c +1140.21 603.00 1139.40 602.19 1139.40 601.20 c +1139.40 600.21 1140.21 599.40 1141.20 599.40 c +1142.19 599.40 1143.00 600.21 1143.00 601.20 c +f +0.80 0.00 0.00 rg +1171.80 496.80 m 1171.80 497.79 1170.99 498.60 1170.00 498.60 c +1169.01 498.60 1168.20 497.79 1168.20 496.80 c +1168.20 495.81 1169.01 495.00 1170.00 495.00 c +1170.99 495.00 1171.80 495.81 1171.80 496.80 c +f +0.80 0.00 0.00 rg +1171.80 457.20 m 1171.80 458.19 1170.99 459.00 1170.00 459.00 c +1169.01 459.00 1168.20 458.19 1168.20 457.20 c +1168.20 456.21 1169.01 455.40 1170.00 455.40 c +1170.99 455.40 1171.80 456.21 1171.80 457.20 c +f +0.80 0.00 0.00 rg +1031.40 464.40 m 1031.40 465.39 1030.59 466.20 1029.60 466.20 c +1028.61 466.20 1027.80 465.39 1027.80 464.40 c +1027.80 463.41 1028.61 462.60 1029.60 462.60 c +1030.59 462.60 1031.40 463.41 1031.40 464.40 c +f +0.80 0.00 0.00 rg +1002.60 464.40 m 1002.60 465.39 1001.79 466.20 1000.80 466.20 c +999.81 466.20 999.00 465.39 999.00 464.40 c +999.00 463.41 999.81 462.60 1000.80 462.60 c +1001.79 462.60 1002.60 463.41 1002.60 464.40 c +f +0.80 0.00 0.00 rg +1031.40 439.20 m 1031.40 440.19 1030.59 441.00 1029.60 441.00 c +1028.61 441.00 1027.80 440.19 1027.80 439.20 c +1027.80 438.21 1028.61 437.40 1029.60 437.40 c +1030.59 437.40 1031.40 438.21 1031.40 439.20 c +f +0.80 0.00 0.00 rg +693.00 446.40 m 693.00 447.39 692.19 448.20 691.20 448.20 c +690.21 448.20 689.40 447.39 689.40 446.40 c +689.40 445.41 690.21 444.60 691.20 444.60 c +692.19 444.60 693.00 445.41 693.00 446.40 c +f +0.80 0.00 0.00 rg +693.00 403.20 m 693.00 404.19 692.19 405.00 691.20 405.00 c +690.21 405.00 689.40 404.19 689.40 403.20 c +689.40 402.21 690.21 401.40 691.20 401.40 c +692.19 401.40 693.00 402.21 693.00 403.20 c +f +0.80 0.00 0.00 rg +793.80 399.60 m 793.80 400.59 792.99 401.40 792.00 401.40 c +791.01 401.40 790.20 400.59 790.20 399.60 c +790.20 398.61 791.01 397.80 792.00 397.80 c +792.99 397.80 793.80 398.61 793.80 399.60 c +f +0.80 0.00 0.00 rg +819.00 712.80 m 819.00 713.79 818.19 714.60 817.20 714.60 c +816.21 714.60 815.40 713.79 815.40 712.80 c +815.40 711.81 816.21 711.00 817.20 711.00 c +818.19 711.00 819.00 711.81 819.00 712.80 c +f +0.80 0.00 0.00 rg +811.80 712.80 m 811.80 713.79 810.99 714.60 810.00 714.60 c +809.01 714.60 808.20 713.79 808.20 712.80 c +808.20 711.81 809.01 711.00 810.00 711.00 c +810.99 711.00 811.80 711.81 811.80 712.80 c +f +0.80 0.00 0.00 rg +804.60 712.80 m 804.60 713.79 803.79 714.60 802.80 714.60 c +801.81 714.60 801.00 713.79 801.00 712.80 c +801.00 711.81 801.81 711.00 802.80 711.00 c +803.79 711.00 804.60 711.81 804.60 712.80 c +f +0.80 0.00 0.00 rg +797.40 712.80 m 797.40 713.79 796.59 714.60 795.60 714.60 c +794.61 714.60 793.80 713.79 793.80 712.80 c +793.80 711.81 794.61 711.00 795.60 711.00 c +796.59 711.00 797.40 711.81 797.40 712.80 c +f +0.80 0.00 0.00 rg +790.20 712.80 m 790.20 713.79 789.39 714.60 788.40 714.60 c +787.41 714.60 786.60 713.79 786.60 712.80 c +786.60 711.81 787.41 711.00 788.40 711.00 c +789.39 711.00 790.20 711.81 790.20 712.80 c +f +0.80 0.00 0.00 rg +783.00 712.80 m 783.00 713.79 782.19 714.60 781.20 714.60 c +780.21 714.60 779.40 713.79 779.40 712.80 c +779.40 711.81 780.21 711.00 781.20 711.00 c +782.19 711.00 783.00 711.81 783.00 712.80 c +f +0.80 0.00 0.00 rg +768.60 712.80 m 768.60 713.79 767.79 714.60 766.80 714.60 c +765.81 714.60 765.00 713.79 765.00 712.80 c +765.00 711.81 765.81 711.00 766.80 711.00 c +767.79 711.00 768.60 711.81 768.60 712.80 c +f +0.80 0.00 0.00 rg +855.00 745.20 m 855.00 746.19 854.19 747.00 853.20 747.00 c +852.21 747.00 851.40 746.19 851.40 745.20 c +851.40 744.21 852.21 743.40 853.20 743.40 c +854.19 743.40 855.00 744.21 855.00 745.20 c +f +0.80 0.00 0.00 rg +876.60 745.20 m 876.60 746.19 875.79 747.00 874.80 747.00 c +873.81 747.00 873.00 746.19 873.00 745.20 c +873.00 744.21 873.81 743.40 874.80 743.40 c +875.79 743.40 876.60 744.21 876.60 745.20 c +f +0.80 0.00 0.00 rg +898.20 745.20 m 898.20 746.19 897.39 747.00 896.40 747.00 c +895.41 747.00 894.60 746.19 894.60 745.20 c +894.60 744.21 895.41 743.40 896.40 743.40 c +897.39 743.40 898.20 744.21 898.20 745.20 c +f +0.80 0.00 0.00 rg +919.80 745.20 m 919.80 746.19 918.99 747.00 918.00 747.00 c +917.01 747.00 916.20 746.19 916.20 745.20 c +916.20 744.21 917.01 743.40 918.00 743.40 c +918.99 743.40 919.80 744.21 919.80 745.20 c +f +0.80 0.00 0.00 rg +829.80 712.80 m 829.80 713.79 828.99 714.60 828.00 714.60 c +827.01 714.60 826.20 713.79 826.20 712.80 c +826.20 711.81 827.01 711.00 828.00 711.00 c +828.99 711.00 829.80 711.81 829.80 712.80 c +f +0.80 0.00 0.00 rg +743.40 712.80 m 743.40 713.79 742.59 714.60 741.60 714.60 c +740.61 714.60 739.80 713.79 739.80 712.80 c +739.80 711.81 740.61 711.00 741.60 711.00 c +742.59 711.00 743.40 711.81 743.40 712.80 c +f +0.80 0.00 0.00 rg +757.80 712.80 m 757.80 713.79 756.99 714.60 756.00 714.60 c +755.01 714.60 754.20 713.79 754.20 712.80 c +754.20 711.81 755.01 711.00 756.00 711.00 c +756.99 711.00 757.80 711.81 757.80 712.80 c +f +0.80 0.00 0.00 rg +718.20 745.20 m 718.20 746.19 717.39 747.00 716.40 747.00 c +715.41 747.00 714.60 746.19 714.60 745.20 c +714.60 744.21 715.41 743.40 716.40 743.40 c +717.39 743.40 718.20 744.21 718.20 745.20 c +f +0.80 0.00 0.00 rg +700.20 745.20 m 700.20 746.19 699.39 747.00 698.40 747.00 c +697.41 747.00 696.60 746.19 696.60 745.20 c +696.60 744.21 697.41 743.40 698.40 743.40 c +699.39 743.40 700.20 744.21 700.20 745.20 c +f +0.80 0.00 0.00 rg +1089.00 709.20 m 1089.00 710.19 1088.19 711.00 1087.20 711.00 c +1086.21 711.00 1085.40 710.19 1085.40 709.20 c +1085.40 708.21 1086.21 707.40 1087.20 707.40 c +1088.19 707.40 1089.00 708.21 1089.00 709.20 c +f +0.80 0.00 0.00 rg +1081.80 716.40 m 1081.80 717.39 1080.99 718.20 1080.00 718.20 c +1079.01 718.20 1078.20 717.39 1078.20 716.40 c +1078.20 715.41 1079.01 714.60 1080.00 714.60 c +1080.99 714.60 1081.80 715.41 1081.80 716.40 c +f +0.80 0.00 0.00 rg +1171.80 738.00 m 1171.80 738.99 1170.99 739.80 1170.00 739.80 c +1169.01 739.80 1168.20 738.99 1168.20 738.00 c +1168.20 737.01 1169.01 736.20 1170.00 736.20 c +1170.99 736.20 1171.80 737.01 1171.80 738.00 c +f +0.80 0.00 0.00 rg +1171.80 694.80 m 1171.80 695.79 1170.99 696.60 1170.00 696.60 c +1169.01 696.60 1168.20 695.79 1168.20 694.80 c +1168.20 693.81 1169.01 693.00 1170.00 693.00 c +1170.99 693.00 1171.80 693.81 1171.80 694.80 c +f +0.80 0.00 0.00 rg +527.40 734.40 m 527.40 735.39 526.59 736.20 525.60 736.20 c +524.61 736.20 523.80 735.39 523.80 734.40 c +523.80 733.41 524.61 732.60 525.60 732.60 c +526.59 732.60 527.40 733.41 527.40 734.40 c +f +0.80 0.00 0.00 rg +491.40 734.40 m 491.40 735.39 490.59 736.20 489.60 736.20 c +488.61 736.20 487.80 735.39 487.80 734.40 c +487.80 733.41 488.61 732.60 489.60 732.60 c +490.59 732.60 491.40 733.41 491.40 734.40 c +f +0.80 0.00 0.00 rg +567.00 730.80 m 567.00 731.79 566.19 732.60 565.20 732.60 c +564.21 732.60 563.40 731.79 563.40 730.80 c +563.40 729.81 564.21 729.00 565.20 729.00 c +566.19 729.00 567.00 729.81 567.00 730.80 c +f +0.80 0.00 0.00 rg +502.20 579.60 m 502.20 580.59 501.39 581.40 500.40 581.40 c +499.41 581.40 498.60 580.59 498.60 579.60 c +498.60 578.61 499.41 577.80 500.40 577.80 c +501.39 577.80 502.20 578.61 502.20 579.60 c +f +0.80 0.00 0.00 rg +588.60 558.00 m 588.60 558.99 587.79 559.80 586.80 559.80 c +585.81 559.80 585.00 558.99 585.00 558.00 c +585.00 557.01 585.81 556.20 586.80 556.20 c +587.79 556.20 588.60 557.01 588.60 558.00 c +f +0.80 0.00 0.00 rg +502.20 529.20 m 502.20 530.19 501.39 531.00 500.40 531.00 c +499.41 531.00 498.60 530.19 498.60 529.20 c +498.60 528.21 499.41 527.40 500.40 527.40 c +501.39 527.40 502.20 528.21 502.20 529.20 c +f +0.80 0.00 0.00 rg +196.20 435.60 m 196.20 436.59 195.39 437.40 194.40 437.40 c +193.41 437.40 192.60 436.59 192.60 435.60 c +192.60 434.61 193.41 433.80 194.40 433.80 c +195.39 433.80 196.20 434.61 196.20 435.60 c +f +0.80 0.00 0.00 rg +196.20 424.80 m 196.20 425.79 195.39 426.60 194.40 426.60 c +193.41 426.60 192.60 425.79 192.60 424.80 c +192.60 423.81 193.41 423.00 194.40 423.00 c +195.39 423.00 196.20 423.81 196.20 424.80 c +f +0.80 0.00 0.00 rg +196.20 417.60 m 196.20 418.59 195.39 419.40 194.40 419.40 c +193.41 419.40 192.60 418.59 192.60 417.60 c +192.60 416.61 193.41 415.80 194.40 415.80 c +195.39 415.80 196.20 416.61 196.20 417.60 c +f +0.80 0.00 0.00 rg +225.00 428.40 m 225.00 429.39 224.19 430.20 223.20 430.20 c +222.21 430.20 221.40 429.39 221.40 428.40 c +221.40 427.41 222.21 426.60 223.20 426.60 c +224.19 426.60 225.00 427.41 225.00 428.40 c +f +0.80 0.00 0.00 rg +333.00 442.80 m 333.00 443.79 332.19 444.60 331.20 444.60 c +330.21 444.60 329.40 443.79 329.40 442.80 c +329.40 441.81 330.21 441.00 331.20 441.00 c +332.19 441.00 333.00 441.81 333.00 442.80 c +f +0.80 0.00 0.00 rg +304.20 399.60 m 304.20 400.59 303.39 401.40 302.40 401.40 c +301.41 401.40 300.60 400.59 300.60 399.60 c +300.60 398.61 301.41 397.80 302.40 397.80 c +303.39 397.80 304.20 398.61 304.20 399.60 c +f +0.80 0.00 0.00 rg +261.00 385.20 m 261.00 386.19 260.19 387.00 259.20 387.00 c +258.21 387.00 257.40 386.19 257.40 385.20 c +257.40 384.21 258.21 383.40 259.20 383.40 c +260.19 383.40 261.00 384.21 261.00 385.20 c +f +0.80 0.00 0.00 rg +289.80 453.60 m 289.80 454.59 288.99 455.40 288.00 455.40 c +287.01 455.40 286.20 454.59 286.20 453.60 c +286.20 452.61 287.01 451.80 288.00 451.80 c +288.99 451.80 289.80 452.61 289.80 453.60 c +f +0.80 0.00 0.00 rg +261.00 453.60 m 261.00 454.59 260.19 455.40 259.20 455.40 c +258.21 455.40 257.40 454.59 257.40 453.60 c +257.40 452.61 258.21 451.80 259.20 451.80 c +260.19 451.80 261.00 452.61 261.00 453.60 c +f +0.80 0.00 0.00 rg +221.40 252.00 m 221.40 252.99 220.59 253.80 219.60 253.80 c +218.61 253.80 217.80 252.99 217.80 252.00 c +217.80 251.01 218.61 250.20 219.60 250.20 c +220.59 250.20 221.40 251.01 221.40 252.00 c +f +0.80 0.00 0.00 rg +131.40 302.40 m 131.40 303.39 130.59 304.20 129.60 304.20 c +128.61 304.20 127.80 303.39 127.80 302.40 c +127.80 301.41 128.61 300.60 129.60 300.60 c +130.59 300.60 131.40 301.41 131.40 302.40 c +f +0.80 0.00 0.00 rg +81.00 288.00 m 81.00 288.99 80.19 289.80 79.20 289.80 c +78.21 289.80 77.40 288.99 77.40 288.00 c +77.40 287.01 78.21 286.20 79.20 286.20 c +80.19 286.20 81.00 287.01 81.00 288.00 c +f +0.80 0.00 0.00 rg +354.60 288.00 m 354.60 288.99 353.79 289.80 352.80 289.80 c +351.81 289.80 351.00 288.99 351.00 288.00 c +351.00 287.01 351.81 286.20 352.80 286.20 c +353.79 286.20 354.60 287.01 354.60 288.00 c +f +0.80 0.00 0.00 rg +351.00 252.00 m 351.00 252.99 350.19 253.80 349.20 253.80 c +348.21 253.80 347.40 252.99 347.40 252.00 c +347.40 251.01 348.21 250.20 349.20 250.20 c +350.19 250.20 351.00 251.01 351.00 252.00 c +f +0.80 0.00 0.00 rg +297.00 306.00 m 297.00 306.99 296.19 307.80 295.20 307.80 c +294.21 307.80 293.40 306.99 293.40 306.00 c +293.40 305.01 294.21 304.20 295.20 304.20 c +296.19 304.20 297.00 305.01 297.00 306.00 c +f +0.80 0.00 0.00 rg +297.00 237.60 m 297.00 238.59 296.19 239.40 295.20 239.40 c +294.21 239.40 293.40 238.59 293.40 237.60 c +293.40 236.61 294.21 235.80 295.20 235.80 c +296.19 235.80 297.00 236.61 297.00 237.60 c +f +0.80 0.00 0.00 rg +286.20 270.00 m 286.20 270.99 285.39 271.80 284.40 271.80 c +283.41 271.80 282.60 270.99 282.60 270.00 c +282.60 269.01 283.41 268.20 284.40 268.20 c +285.39 268.20 286.20 269.01 286.20 270.00 c +f +0.80 0.00 0.00 rg +419.40 273.60 m 419.40 274.59 418.59 275.40 417.60 275.40 c +416.61 275.40 415.80 274.59 415.80 273.60 c +415.80 272.61 416.61 271.80 417.60 271.80 c +418.59 271.80 419.40 272.61 419.40 273.60 c +f +0.80 0.00 0.00 rg +426.60 266.40 m 426.60 267.39 425.79 268.20 424.80 268.20 c +423.81 268.20 423.00 267.39 423.00 266.40 c +423.00 265.41 423.81 264.60 424.80 264.60 c +425.79 264.60 426.60 265.41 426.60 266.40 c +f +0.80 0.00 0.00 rg +426.60 302.40 m 426.60 303.39 425.79 304.20 424.80 304.20 c +423.81 304.20 423.00 303.39 423.00 302.40 c +423.00 301.41 423.81 300.60 424.80 300.60 c +425.79 300.60 426.60 301.41 426.60 302.40 c +f +0.80 0.00 0.00 rg +415.80 439.20 m 415.80 440.19 414.99 441.00 414.00 441.00 c +413.01 441.00 412.20 440.19 412.20 439.20 c +412.20 438.21 413.01 437.40 414.00 437.40 c +414.99 437.40 415.80 438.21 415.80 439.20 c +f +0.80 0.00 0.00 rg +415.80 396.00 m 415.80 396.99 414.99 397.80 414.00 397.80 c +413.01 397.80 412.20 396.99 412.20 396.00 c +412.20 395.01 413.01 394.20 414.00 394.20 c +414.99 394.20 415.80 395.01 415.80 396.00 c +f +0.80 0.00 0.00 rg +437.40 414.00 m 437.40 414.99 436.59 415.80 435.60 415.80 c +434.61 415.80 433.80 414.99 433.80 414.00 c +433.80 413.01 434.61 412.20 435.60 412.20 c +436.59 412.20 437.40 413.01 437.40 414.00 c +f +0.80 0.00 0.00 rg +480.60 385.20 m 480.60 386.19 479.79 387.00 478.80 387.00 c +477.81 387.00 477.00 386.19 477.00 385.20 c +477.00 384.21 477.81 383.40 478.80 383.40 c +479.79 383.40 480.60 384.21 480.60 385.20 c +f +0.80 0.00 0.00 rg +437.40 374.40 m 437.40 375.39 436.59 376.20 435.60 376.20 c +434.61 376.20 433.80 375.39 433.80 374.40 c +433.80 373.41 434.61 372.60 435.60 372.60 c +436.59 372.60 437.40 373.41 437.40 374.40 c +f +0.80 0.00 0.00 rg +415.80 374.40 m 415.80 375.39 414.99 376.20 414.00 376.20 c +413.01 376.20 412.20 375.39 412.20 374.40 c +412.20 373.41 413.01 372.60 414.00 372.60 c +414.99 372.60 415.80 373.41 415.80 374.40 c +f +0.80 0.00 0.00 rg +185.40 104.40 m 185.40 105.39 184.59 106.20 183.60 106.20 c +182.61 106.20 181.80 105.39 181.80 104.40 c +181.80 103.41 182.61 102.60 183.60 102.60 c +184.59 102.60 185.40 103.41 185.40 104.40 c +f +0.80 0.00 0.00 rg +174.60 104.40 m 174.60 105.39 173.79 106.20 172.80 106.20 c +171.81 106.20 171.00 105.39 171.00 104.40 c +171.00 103.41 171.81 102.60 172.80 102.60 c +173.79 102.60 174.60 103.41 174.60 104.40 c +f +0.80 0.00 0.00 rg +149.40 104.40 m 149.40 105.39 148.59 106.20 147.60 106.20 c +146.61 106.20 145.80 105.39 145.80 104.40 c +145.80 103.41 146.61 102.60 147.60 102.60 c +148.59 102.60 149.40 103.41 149.40 104.40 c +f +0.80 0.00 0.00 rg +145.80 126.00 m 145.80 126.99 144.99 127.80 144.00 127.80 c +143.01 127.80 142.20 126.99 142.20 126.00 c +142.20 125.01 143.01 124.20 144.00 124.20 c +144.99 124.20 145.80 125.01 145.80 126.00 c +f +0.80 0.00 0.00 rg +315.00 86.40 m 315.00 87.39 314.19 88.20 313.20 88.20 c +312.21 88.20 311.40 87.39 311.40 86.40 c +311.40 85.41 312.21 84.60 313.20 84.60 c +314.19 84.60 315.00 85.41 315.00 86.40 c +f +0.80 0.00 0.00 rg +268.20 79.20 m 268.20 80.19 267.39 81.00 266.40 81.00 c +265.41 81.00 264.60 80.19 264.60 79.20 c +264.60 78.21 265.41 77.40 266.40 77.40 c +267.39 77.40 268.20 78.21 268.20 79.20 c +f +0.80 0.00 0.00 rg +329.40 75.60 m 329.40 76.59 328.59 77.40 327.60 77.40 c +326.61 77.40 325.80 76.59 325.80 75.60 c +325.80 74.61 326.61 73.80 327.60 73.80 c +328.59 73.80 329.40 74.61 329.40 75.60 c +f +0.80 0.00 0.00 rg +275.40 72.00 m 275.40 72.99 274.59 73.80 273.60 73.80 c +272.61 73.80 271.80 72.99 271.80 72.00 c +271.80 71.01 272.61 70.20 273.60 70.20 c +274.59 70.20 275.40 71.01 275.40 72.00 c +f +0.80 0.00 0.00 rg +1315.80 529.20 m 1315.80 530.19 1314.99 531.00 1314.00 531.00 c +1313.01 531.00 1312.20 530.19 1312.20 529.20 c +1312.20 528.21 1313.01 527.40 1314.00 527.40 c +1314.99 527.40 1315.80 528.21 1315.80 529.20 c +f +0.80 0.00 0.00 rg +1315.80 536.40 m 1315.80 537.39 1314.99 538.20 1314.00 538.20 c +1313.01 538.20 1312.20 537.39 1312.20 536.40 c +1312.20 535.41 1313.01 534.60 1314.00 534.60 c +1314.99 534.60 1315.80 535.41 1315.80 536.40 c +f +0.80 0.00 0.00 rg +1312.20 698.40 m 1312.20 699.39 1311.39 700.20 1310.40 700.20 c +1309.41 700.20 1308.60 699.39 1308.60 698.40 c +1308.60 697.41 1309.41 696.60 1310.40 696.60 c +1311.39 696.60 1312.20 697.41 1312.20 698.40 c +f +0.80 0.00 0.00 rg +419.40 144.00 m 419.40 144.99 418.59 145.80 417.60 145.80 c +416.61 145.80 415.80 144.99 415.80 144.00 c +415.80 143.01 416.61 142.20 417.60 142.20 c +418.59 142.20 419.40 143.01 419.40 144.00 c +f +0.80 0.00 0.00 rg +419.40 104.40 m 419.40 105.39 418.59 106.20 417.60 106.20 c +416.61 106.20 415.80 105.39 415.80 104.40 c +415.80 103.41 416.61 102.60 417.60 102.60 c +418.59 102.60 419.40 103.41 419.40 104.40 c +f +0.80 0.00 0.00 rg +423.00 64.80 m 423.00 65.79 422.19 66.60 421.20 66.60 c +420.21 66.60 419.40 65.79 419.40 64.80 c +419.40 63.81 420.21 63.00 421.20 63.00 c +422.19 63.00 423.00 63.81 423.00 64.80 c +f +0.80 0.00 0.00 rg +772.20 205.20 m 772.20 206.19 771.39 207.00 770.40 207.00 c +769.41 207.00 768.60 206.19 768.60 205.20 c +768.60 204.21 769.41 203.40 770.40 203.40 c +771.39 203.40 772.20 204.21 772.20 205.20 c +f +0.80 0.00 0.00 rg +732.60 140.40 m 732.60 141.39 731.79 142.20 730.80 142.20 c +729.81 142.20 729.00 141.39 729.00 140.40 c +729.00 139.41 729.81 138.60 730.80 138.60 c +731.79 138.60 732.60 139.41 732.60 140.40 c +f +0.80 0.00 0.00 rg +732.60 118.80 m 732.60 119.79 731.79 120.60 730.80 120.60 c +729.81 120.60 729.00 119.79 729.00 118.80 c +729.00 117.81 729.81 117.00 730.80 117.00 c +731.79 117.00 732.60 117.81 732.60 118.80 c +f +0.80 0.00 0.00 rg +732.60 183.60 m 732.60 184.59 731.79 185.40 730.80 185.40 c +729.81 185.40 729.00 184.59 729.00 183.60 c +729.00 182.61 729.81 181.80 730.80 181.80 c +731.79 181.80 732.60 182.61 732.60 183.60 c +f +0.80 0.00 0.00 rg +732.60 205.20 m 732.60 206.19 731.79 207.00 730.80 207.00 c +729.81 207.00 729.00 206.19 729.00 205.20 c +729.00 204.21 729.81 203.40 730.80 203.40 c +731.79 203.40 732.60 204.21 732.60 205.20 c +f +0.80 0.00 0.00 rg +473.40 122.40 m 473.40 123.39 472.59 124.20 471.60 124.20 c +470.61 124.20 469.80 123.39 469.80 122.40 c +469.80 121.41 470.61 120.60 471.60 120.60 c +472.59 120.60 473.40 121.41 473.40 122.40 c +f +0.80 0.00 0.00 rg +473.40 104.40 m 473.40 105.39 472.59 106.20 471.60 106.20 c +470.61 106.20 469.80 105.39 469.80 104.40 c +469.80 103.41 470.61 102.60 471.60 102.60 c +472.59 102.60 473.40 103.41 473.40 104.40 c +f +0.80 0.00 0.00 rg +667.80 162.00 m 667.80 162.99 666.99 163.80 666.00 163.80 c +665.01 163.80 664.20 162.99 664.20 162.00 c +664.20 161.01 665.01 160.20 666.00 160.20 c +666.99 160.20 667.80 161.01 667.80 162.00 c +f +0.80 0.00 0.00 rg +703.80 223.20 m 703.80 224.19 702.99 225.00 702.00 225.00 c +701.01 225.00 700.20 224.19 700.20 223.20 c +700.20 222.21 701.01 221.40 702.00 221.40 c +702.99 221.40 703.80 222.21 703.80 223.20 c +f +0.80 0.00 0.00 rg +653.40 306.00 m 653.40 306.99 652.59 307.80 651.60 307.80 c +650.61 307.80 649.80 306.99 649.80 306.00 c +649.80 305.01 650.61 304.20 651.60 304.20 c +652.59 304.20 653.40 305.01 653.40 306.00 c +f +0.80 0.00 0.00 rg +700.20 61.20 m 700.20 62.19 699.39 63.00 698.40 63.00 c +697.41 63.00 696.60 62.19 696.60 61.20 c +696.60 60.21 697.41 59.40 698.40 59.40 c +699.39 59.40 700.20 60.21 700.20 61.20 c +f +0.80 0.00 0.00 rg +750.60 72.00 m 750.60 72.99 749.79 73.80 748.80 73.80 c +747.81 73.80 747.00 72.99 747.00 72.00 c +747.00 71.01 747.81 70.20 748.80 70.20 c +749.79 70.20 750.60 71.01 750.60 72.00 c +f +0.80 0.00 0.00 rg +729.00 72.00 m 729.00 72.99 728.19 73.80 727.20 73.80 c +726.21 73.80 725.40 72.99 725.40 72.00 c +725.40 71.01 726.21 70.20 727.20 70.20 c +728.19 70.20 729.00 71.01 729.00 72.00 c +f +0.80 0.00 0.00 rg +700.20 100.80 m 700.20 101.79 699.39 102.60 698.40 102.60 c +697.41 102.60 696.60 101.79 696.60 100.80 c +696.60 99.81 697.41 99.00 698.40 99.00 c +699.39 99.00 700.20 99.81 700.20 100.80 c +f +0.80 0.00 0.00 rg +729.00 100.80 m 729.00 101.79 728.19 102.60 727.20 102.60 c +726.21 102.60 725.40 101.79 725.40 100.80 c +725.40 99.81 726.21 99.00 727.20 99.00 c +728.19 99.00 729.00 99.81 729.00 100.80 c +f +0.80 0.00 0.00 rg +750.60 100.80 m 750.60 101.79 749.79 102.60 748.80 102.60 c +747.81 102.60 747.00 101.79 747.00 100.80 c +747.00 99.81 747.81 99.00 748.80 99.00 c +749.79 99.00 750.60 99.81 750.60 100.80 c +f +0.80 0.00 0.00 rg +700.20 270.00 m 700.20 270.99 699.39 271.80 698.40 271.80 c +697.41 271.80 696.60 270.99 696.60 270.00 c +696.60 269.01 697.41 268.20 698.40 268.20 c +699.39 268.20 700.20 269.01 700.20 270.00 c +f +0.80 0.00 0.00 rg +736.20 270.00 m 736.20 270.99 735.39 271.80 734.40 271.80 c +733.41 271.80 732.60 270.99 732.60 270.00 c +732.60 269.01 733.41 268.20 734.40 268.20 c +735.39 268.20 736.20 269.01 736.20 270.00 c +f +0.80 0.00 0.00 rg +757.80 306.00 m 757.80 306.99 756.99 307.80 756.00 307.80 c +755.01 307.80 754.20 306.99 754.20 306.00 c +754.20 305.01 755.01 304.20 756.00 304.20 c +756.99 304.20 757.80 305.01 757.80 306.00 c +f +0.80 0.00 0.00 rg +736.20 306.00 m 736.20 306.99 735.39 307.80 734.40 307.80 c +733.41 307.80 732.60 306.99 732.60 306.00 c +732.60 305.01 733.41 304.20 734.40 304.20 c +735.39 304.20 736.20 305.01 736.20 306.00 c +f +0.80 0.00 0.00 rg +1315.80 493.20 m 1315.80 494.19 1314.99 495.00 1314.00 495.00 c +1313.01 495.00 1312.20 494.19 1312.20 493.20 c +1312.20 492.21 1313.01 491.40 1314.00 491.40 c +1314.99 491.40 1315.80 492.21 1315.80 493.20 c +f +Q +endstream +endobj +1 0 obj +<> +endobj +5 0 obj +<< +/Type /FontDescriptor +/FontName /SimSun +/FontBBox [-8 -145 1000 859] +/Flags 32 +/StemV 0 +/ItalicAngle 0 +/Ascent 859 +/Descent -141 +/CapHeight 175 +>> +endobj +6 0 obj +<< +/Type /Font +/BaseFont /SimSun +/FontDescriptor 5 0 R +/W [1 95 500] +/Subtype /CIDFontType2 +/CIDSystemInfo +<< +/Ordering (GB1) +/Registry (Adobe) +/Supplement 2 +>> +>> +endobj +7 0 obj +<< +/Type /Font +/Subtype /Type0 +/BaseFont /SimSun +/Encoding /UniGB-UCS2-H +/DescendantFonts [6 0 R] +>> +endobj +8 0 obj +<< +/Descent -325 +/CapHeight 500 +/StemV 80 +/Type /FontDescriptor +/Flags 32 +/FontBBox [-665 -325 2000 1006] +/FontName /Arial +/ItalicAngle 0 +/Ascent 1006 +>> +endobj +9 0 obj +<> +endobj +10 0 obj +<< +/Type /FontDescriptor +/FontName /SimHei +/FontBBox [-11 -156 996 859] +/Flags 32 +/StemV 0 +/ItalicAngle 0 +/Ascent 859 +/Descent -140 +/CapHeight 687 +>> +endobj +11 0 obj +<< +/Type /Font +/BaseFont /SimHei +/FontDescriptor 10 0 R +/W [1 95 500 738 813 1000] +/Subtype /CIDFontType2 +/CIDSystemInfo +<< +/Ordering (GB1) +/Registry (Adobe) +/Supplement 2 +>> +>> +endobj +12 0 obj +<< +/Type /Font +/Subtype /Type0 +/BaseFont /SimHei +/Encoding /UniGB-UCS2-H +/DescendantFonts [11 0 R] +>> +endobj +2 0 obj +<< +/ProcSet [/PDF /Text /ImageB /ImageC /ImageI] +/Font << +/F1 7 0 R +/F2 9 0 R +/F3 12 0 R +>> +/XObject << +>> +>> +endobj +13 0 obj +<< +/Producer (jsPDF 0.0.0) +/CreationDate (D:20260225160733-00'00') +>> +endobj +14 0 obj +<< +/Type /Catalog +/Pages 1 0 R +/OpenAction [3 0 R /FitH null] +/PageLayout /OneColumn +>> +endobj +xref +0 15 +0000000000 65535 f +0000445372 00000 n +0000447580 00000 n +0000000015 00000 n +0000000125 00000 n +0000445429 00000 n +0000445594 00000 n +0000445773 00000 n +0000445889 00000 n +0000446058 00000 n +0000447102 00000 n +0000447268 00000 n +0000447462 00000 n +0000447705 00000 n +0000447791 00000 n +trailer +<< +/Size 15 +/Root 14 0 R +/Info 13 0 R +/ID [ <2E97D8067CAD7682BA436D14B49DAB70> <2E97D8067CAD7682BA436D14B49DAB70> ] +>> +startxref +447895 +%%EOF diff --git a/docs/custom-board.md b/docs/custom-board.md new file mode 100644 index 0000000..6349b83 --- /dev/null +++ b/docs/custom-board.md @@ -0,0 +1,452 @@ +# 自定义开发板指南 + +本指南介绍如何为小智AI语音聊天机器人项目定制一个新的开发板初始化程序。小智AI支持70多种ESP32系列开发板,每个开发板的初始化代码都放在对应的目录下。 + +## 重要提示 + +> **警告**: 对于自定义开发板,当IO配置与原有开发板不同时,切勿直接覆盖原有开发板的配置编译固件。必须创建新的开发板类型,或者通过config.json文件中的builds配置不同的name和sdkconfig宏定义来区分。使用 `python scripts/release.py [开发板目录名字]` 来编译打包固件。 +> +> 如果直接覆盖原有配置,将来OTA升级时,您的自定义固件可能会被原有开发板的标准固件覆盖,导致您的设备无法正常工作。每个开发板有唯一的标识和对应的固件升级通道,保持开发板标识的唯一性非常重要。 + +## 目录结构 + +每个开发板的目录结构通常包含以下文件: + +- `xxx_board.cc` - 主要的板级初始化代码,实现了板子相关的初始化和功能 +- `config.h` - 板级配置文件,定义了硬件管脚映射和其他配置项 +- `config.json` - 编译配置,指定目标芯片和特殊的编译选项 +- `README.md` - 开发板相关的说明文档 + +## 定制开发板步骤 + +### 1. 创建新的开发板目录 + +首先在`boards/`目录下创建一个新的目录,命名方式应使用 `[品牌名]-[开发板类型]` 的形式,例如 `m5stack-tab5`: + +```bash +mkdir main/boards/my-custom-board +``` + +### 2. 创建配置文件 + +#### config.h + +在`config.h`中定义所有的硬件配置,包括: + +- 音频采样率和I2S引脚配置 +- 音频编解码芯片地址和I2C引脚配置 +- 按钮和LED引脚配置 +- 显示屏参数和引脚配置 + +参考示例(来自lichuang-c3-dev): + +```c +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +// 音频配置 +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_13 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_0 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +// 按钮配置 +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + +// 显示屏配置 +#define DISPLAY_SPI_SCK_PIN GPIO_NUM_3 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_6 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_4 + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_2 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ +``` + +#### config.json + +在`config.json`中定义编译配置,这个文件用于 `scripts/release.py` 脚本自动化编译: + +```json +{ + "target": "esp32s3", // 目标芯片型号: esp32, esp32s3, esp32c3, esp32c6, esp32p4等 + "builds": [ + { + "name": "my-custom-board", // 开发板名称,用于生成固件包 + "sdkconfig_append": [ + // 特别 Flash 大小配置 + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + // 特别分区表配置 + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"" + ] + } + ] +} +``` + +**配置项说明:** +- `target`: 目标芯片型号,必须与硬件匹配 +- `name`: 编译输出的固件包名称,建议与目录名一致 +- `sdkconfig_append`: 额外的 sdkconfig 配置项数组,会追加到默认配置中 + +**常用的 sdkconfig_append 配置:** +```json +// Flash 大小 +"CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y" // 4MB Flash +"CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y" // 8MB Flash +"CONFIG_ESPTOOLPY_FLASHSIZE_16MB=y" // 16MB Flash + +// 分区表 +"CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/4m.csv\"" // 4MB 分区表 +"CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"" // 8MB 分区表 +"CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/16m.csv\"" // 16MB 分区表 + +// 语言配置 +"CONFIG_LANGUAGE_EN_US=y" // 英语 +"CONFIG_LANGUAGE_ZH_CN=y" // 简体中文 + +// 唤醒词配置 +"CONFIG_USE_DEVICE_AEC=y" // 启用设备端 AEC +"CONFIG_WAKE_WORD_DISABLED=y" // 禁用唤醒词 +``` + +### 3. 编写板级初始化代码 + +创建一个`my_custom_board.cc`文件,实现开发板的所有初始化逻辑。 + +一个基本的开发板类定义包含以下几个部分: + +1. **类定义**:继承自`WifiBoard`或`Ml307Board` +2. **初始化函数**:包括I2C、显示屏、按钮、IoT等组件的初始化 +3. **虚函数重写**:如`GetAudioCodec()`、`GetDisplay()`、`GetBacklight()`等 +4. **注册开发板**:使用`DECLARE_BOARD`宏注册开发板 + +```cpp +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" + +#include +#include +#include + +#define TAG "MyCustomBoard" + +class MyCustomBoard : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + // I2C初始化 + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + // SPI初始化(用于显示屏) + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SPI_SCK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + // 按钮初始化 + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + // 显示屏初始化(以ST7789为例) + void InitializeDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 2; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + // 创建显示屏对象 + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + // MCP Tools 初始化 + void InitializeTools() { + // 参考 MCP 文档 + } + +public: + // 构造函数 + MyCustomBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeDisplay(); + InitializeButtons(); + InitializeTools(); + GetBacklight()->SetBrightness(100); + } + + // 获取音频编解码器 + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + codec_i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + // 获取显示屏 + virtual Display* GetDisplay() override { + return display_; + } + + // 获取背光控制 + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +// 注册开发板 +DECLARE_BOARD(MyCustomBoard); +``` + +### 4. 添加构建系统配置 + +#### 在 Kconfig.projbuild 中添加开发板选项 + +打开 `main/Kconfig.projbuild` 文件,在 `choice BOARD_TYPE` 部分添加新的开发板配置项: + +```kconfig +choice BOARD_TYPE + prompt "Board Type" + default BOARD_TYPE_BREAD_COMPACT_WIFI + help + Board type. 开发板类型 + + # ... 其他开发板选项 ... + + config BOARD_TYPE_MY_CUSTOM_BOARD + bool "My Custom Board (我的自定义开发板)" + depends on IDF_TARGET_ESP32S3 # 根据你的目标芯片修改 +endchoice +``` + +**注意事项:** +- `BOARD_TYPE_MY_CUSTOM_BOARD` 是配置项名称,需要全大写,使用下划线分隔 +- `depends on` 指定了目标芯片类型(如 `IDF_TARGET_ESP32S3`、`IDF_TARGET_ESP32C3` 等) +- 描述文字可以使用中英文 + +#### 在 CMakeLists.txt 中添加开发板配置 + +打开 `main/CMakeLists.txt` 文件,在开发板类型判断部分添加新的配置: + +```cmake +# 在 elseif 链中添加你的开发板配置 +elseif(CONFIG_BOARD_TYPE_MY_CUSTOM_BOARD) + set(BOARD_TYPE "my-custom-board") # 与目录名一致 + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) # 根据屏幕大小选择合适的字体 + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) # 可选,如果需要表情显示 +endif() +``` + +**字体和表情配置说明:** + +根据屏幕分辨率选择合适的字体大小: +- 小屏幕(128x64 OLED):`font_puhui_basic_14_1` / `font_awesome_14_1` +- 中小屏幕(240x240):`font_puhui_basic_16_4` / `font_awesome_16_4` +- 中等屏幕(240x320):`font_puhui_basic_20_4` / `font_awesome_20_4` +- 大屏幕(480x320+):`font_puhui_basic_30_4` / `font_awesome_30_4` + +表情集合选项: +- `twemoji_32` - 32x32 像素表情(小屏幕) +- `twemoji_64` - 64x64 像素表情(大屏幕) + +### 5. 配置和编译 + +#### 方法一:使用 idf.py 手动配置 + +1. **设置目标芯片**(首次配置或更换芯片时): + ```bash + # 对于 ESP32-S3 + idf.py set-target esp32s3 + + # 对于 ESP32-C3 + idf.py set-target esp32c3 + + # 对于 ESP32 + idf.py set-target esp32 + ``` + +2. **清理旧配置**: + ```bash + idf.py fullclean + ``` + +3. **进入配置菜单**: + ```bash + idf.py menuconfig + ``` + + 在菜单中导航到:`Xiaozhi Assistant` -> `Board Type`,选择你的自定义开发板。 + +4. **编译和烧录**: + ```bash + idf.py build + idf.py flash monitor + ``` + +#### 方法二:使用 release.py 脚本(推荐) + +如果你的开发板目录下有 `config.json` 文件,可以使用此脚本自动完成配置和编译: + +```bash +python scripts/release.py my-custom-board +``` + +此脚本会自动: +- 读取 `config.json` 中的 `target` 配置并设置目标芯片 +- 应用 `sdkconfig_append` 中的编译选项 +- 完成编译并打包固件 + +### 6. 创建README.md + +在README.md中说明开发板的特性、硬件要求、编译和烧录步骤: + + +## 常见开发板组件 + +### 1. 显示屏 + +项目支持多种显示屏驱动,包括: +- ST7789 (SPI) +- ILI9341 (SPI) +- SH8601 (QSPI) +- 等... + +### 2. 音频编解码器 + +支持的编解码器包括: +- ES8311 (常用) +- ES7210 (麦克风阵列) +- AW88298 (功放) +- 等... + +### 3. 电源管理 + +一些开发板使用电源管理芯片: +- AXP2101 +- 其他可用的PMIC + +### 4. MCP设备控制 + +可以添加各种MCP工具,让AI能够使用: +- Speaker (扬声器控制) +- Screen (屏幕亮度调节) +- Battery (电池电量读取) +- Light (灯光控制) +- 等... + +## 开发板类继承关系 + +- `Board` - 基础板级类 + - `WifiBoard` - Wi-Fi连接的开发板 + - `Ml307Board` - 使用4G模块的开发板 + - `DualNetworkBoard` - 支持Wi-Fi与4G网络切换的开发板 + +## 开发技巧 + +1. **参考相似的开发板**:如果您的新开发板与现有开发板有相似之处,可以参考现有实现 +2. **分步调试**:先实现基础功能(如显示),再添加更复杂的功能(如音频) +3. **管脚映射**:确保在config.h中正确配置所有管脚映射 +4. **检查硬件兼容性**:确认所有芯片和驱动程序的兼容性 + +## 可能遇到的问题 + +1. **显示屏不正常**:检查SPI配置、镜像设置和颜色反转设置 +2. **音频无输出**:检查I2S配置、PA使能引脚和编解码器地址 +3. **无法连接网络**:检查Wi-Fi凭据和网络配置 +4. **无法与服务器通信**:检查MQTT或WebSocket配置 + +## 参考资料 + +- ESP-IDF 文档: https://docs.espressif.com/projects/esp-idf/ +- LVGL 文档: https://docs.lvgl.io/ +- ESP-SR 文档: https://github.com/espressif/esp-sr \ No newline at end of file diff --git a/docs/mcp-based-graph.jpg b/docs/mcp-based-graph.jpg new file mode 100644 index 0000000..af81cd2 Binary files /dev/null and b/docs/mcp-based-graph.jpg differ diff --git a/docs/mcp-protocol.md b/docs/mcp-protocol.md new file mode 100644 index 0000000..0c8ec90 --- /dev/null +++ b/docs/mcp-protocol.md @@ -0,0 +1,269 @@ +# MCP (Model Context Protocol) 交互流程 + +NOTICE: AI 辅助生成, 在实现后台服务时, 请参照代码确认细节!! + +本项目中的 MCP 协议用于后台 API(MCP 客户端)与 ESP32 设备(MCP 服务器)之间的通信,以便后台能够发现和调用设备提供的功能(工具)。 + +## 协议格式 + +根据代码 (`main/protocols/protocol.cc`, `main/mcp_server.cc`),MCP 消息是封装在基础通信协议(如 WebSocket 或 MQTT)的消息体中的。其内部结构遵循 [JSON-RPC 2.0](https://www.jsonrpc.org/specification) 规范。 + +整体消息结构示例: + +```json +{ + "session_id": "...", // 会话 ID + "type": "mcp", // 消息类型,固定为 "mcp" + "payload": { // JSON-RPC 2.0 负载 + "jsonrpc": "2.0", + "method": "...", // 方法名 (如 "initialize", "tools/list", "tools/call") + "params": { ... }, // 方法参数 (对于 request) + "id": ..., // 请求 ID (对于 request 和 response) + "result": { ... }, // 方法执行结果 (对于 success response) + "error": { ... } // 错误信息 (对于 error response) + } +} +``` + +其中,`payload` 部分是标准的 JSON-RPC 2.0 消息: + +- `jsonrpc`: 固定的字符串 "2.0"。 +- `method`: 要调用的方法名称 (对于 Request)。 +- `params`: 方法的参数,一个结构化值,通常为对象 (对于 Request)。 +- `id`: 请求的标识符,客户端发送请求时提供,服务器响应时原样返回。用于匹配请求和响应。 +- `result`: 方法成功执行时的结果 (对于 Success Response)。 +- `error`: 方法执行失败时的错误信息 (对于 Error Response)。 + +## 交互流程及发送时机 + +MCP 的交互主要围绕客户端(后台 API)发现和调用设备上的“工具”(Tool)进行。 + +1. **连接建立与能力通告** + + - **时机:** 设备启动并成功连接到后台 API 后。 + - **发送方:** 设备。 + - **消息:** 设备发送基础协议的 "hello" 消息给后台 API,消息中包含设备支持的能力列表,例如通过支持 MCP 协议 (`"mcp": true`)。 + - **示例 (非 MCP 负载,而是基础协议消息):** + ```json + { + "type": "hello", + "version": ..., + "features": { + "mcp": true, + ... + }, + "transport": "websocket", // 或 "mqtt" + "audio_params": { ... }, + "session_id": "..." // 设备收到服务器hello后可能设置 + } + ``` + +2. **初始化 MCP 会话** + + - **时机:** 后台 API 收到设备 "hello" 消息,确认设备支持 MCP 后,通常作为 MCP 会话的第一个请求发送。 + - **发送方:** 后台 API (客户端)。 + - **方法:** `initialize` + - **消息 (MCP payload):** + + ```json + { + "jsonrpc": "2.0", + "method": "initialize", + "params": { + "capabilities": { + // 客户端能力,可选 + + // 摄像头视觉相关 + "vision": { + "url": "...", //摄像头: 图片处理地址(必须是http地址, 不是websocket地址) + "token": "..." // url token + } + + // ... 其他客户端能力 + } + }, + "id": 1 // 请求 ID + } + ``` + + - **设备响应时机:** 设备收到 `initialize` 请求并处理后。 + - **设备响应消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "id": 1, // 匹配请求 ID + "result": { + "protocolVersion": "2024-11-05", + "capabilities": { + "tools": {} // 这里的 tools 似乎不列出详细信息,需要 tools/list + }, + "serverInfo": { + "name": "...", // 设备名称 (BOARD_NAME) + "version": "..." // 设备固件版本 + } + } + } + ``` + +3. **发现设备工具列表** + + - **时机:** 后台 API 需要获取设备当前支持的具体功能(工具)列表及其调用方式时。 + - **发送方:** 后台 API (客户端)。 + - **方法:** `tools/list` + - **消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "method": "tools/list", + "params": { + "cursor": "" // 用于分页,首次请求为空字符串 + }, + "id": 2 // 请求 ID + } + ``` + - **设备响应时机:** 设备收到 `tools/list` 请求并生成工具列表后。 + - **设备响应消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "id": 2, // 匹配请求 ID + "result": { + "tools": [ // 工具对象列表 + { + "name": "self.get_device_status", + "description": "...", + "inputSchema": { ... } // 参数 schema + }, + { + "name": "self.audio_speaker.set_volume", + "description": "...", + "inputSchema": { ... } // 参数 schema + } + // ... 更多工具 + ], + "nextCursor": "..." // 如果列表很大需要分页,这里会包含下一个请求的 cursor 值 + } + } + ``` + - **分页处理:** 如果 `nextCursor` 字段非空,客户端需要再次发送 `tools/list` 请求,并在 `params` 中带上这个 `cursor` 值以获取下一页工具。 + +4. **调用设备工具** + + - **时机:** 后台 API 需要执行设备上的某个具体功能时。 + - **发送方:** 后台 API (客户端)。 + - **方法:** `tools/call` + - **消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "method": "tools/call", + "params": { + "name": "self.audio_speaker.set_volume", // 要调用的工具名称 + "arguments": { + // 工具参数,对象格式 + "volume": 50 // 参数名及其值 + } + }, + "id": 3 // 请求 ID + } + ``` + - **设备响应时机:** 设备收到 `tools/call` 请求,执行相应的工具函数后。 + - **设备成功响应消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "id": 3, // 匹配请求 ID + "result": { + "content": [ + // 工具执行结果内容 + { "type": "text", "text": "true" } // 示例:set_volume 返回 bool + ], + "isError": false // 表示成功 + } + } + ``` + - **设备失败响应消息 (MCP payload):** + ```json + { + "jsonrpc": "2.0", + "id": 3, // 匹配请求 ID + "error": { + "code": -32601, // JSON-RPC 错误码,例如 Method not found (-32601) + "message": "Unknown tool: self.non_existent_tool" // 错误描述 + } + } + ``` + +5. **设备主动发送消息 (Notifications)** + - **时机:** 设备内部发生需要通知后台 API 的事件时(例如,状态变化,虽然代码示例中没有明确的工具发送此类消息,但 `Application::SendMcpMessage` 的存在暗示了设备可能主动发送 MCP 消息)。 + - **发送方:** 设备 (服务器)。 + - **方法:** 可能是以 `notifications/` 开头的方法名,或者其他自定义方法。 + - **消息 (MCP payload):** 遵循 JSON-RPC Notification 格式,没有 `id` 字段。 + ```json + { + "jsonrpc": "2.0", + "method": "notifications/state_changed", // 示例方法名 + "params": { + "newState": "idle", + "oldState": "connecting" + } + // 没有 id 字段 + } + ``` + - **后台 API 处理:** 接收到 Notification 后,后台 API 进行相应的处理,但不回复。 + +## 交互图 + +下面是一个简化的交互序列图,展示了主要的 MCP 消息流程: + +```mermaid +sequenceDiagram + participant Device as ESP32 Device + participant BackendAPI as 后台 API (Client) + + Note over Device, BackendAPI: 建立 WebSocket / MQTT 连接 + + Device->>BackendAPI: Hello Message (包含 "mcp": true) + + BackendAPI->>Device: MCP Initialize Request + Note over BackendAPI: method: initialize + Note over BackendAPI: params: { capabilities: ... } + + Device->>BackendAPI: MCP Initialize Response + Note over Device: result: { protocolVersion: ..., serverInfo: ... } + + BackendAPI->>Device: MCP Get Tools List Request + Note over BackendAPI: method: tools/list + Note over BackendAPI: params: { cursor: "" } + + Device->>BackendAPI: MCP Get Tools List Response + Note over Device: result: { tools: [...], nextCursor: ... } + + loop Optional Pagination + BackendAPI->>Device: MCP Get Tools List Request + Note over BackendAPI: method: tools/list + Note over BackendAPI: params: { cursor: "..." } + Device->>BackendAPI: MCP Get Tools List Response + Note over Device: result: { tools: [...], nextCursor: "" } + end + + BackendAPI->>Device: MCP Call Tool Request + Note over BackendAPI: method: tools/call + Note over BackendAPI: params: { name: "...", arguments: { ... } } + + alt Tool Call Successful + Device->>BackendAPI: MCP Tool Call Success Response + Note over Device: result: { content: [...], isError: false } + else Tool Call Failed + Device->>BackendAPI: MCP Tool Call Error Response + Note over Device: error: { code: ..., message: ... } + end + + opt Device Notification + Device->>BackendAPI: MCP Notification + Note over Device: method: notifications/... + Note over Device: params: { ... } + end +``` + +这份文档概述了该项目中 MCP 协议的主要交互流程。具体的参数细节和工具功能需要参考 `main/mcp_server.cc` 中 `McpServer::AddCommonTools` 以及各个工具的实现。 diff --git a/docs/mcp-usage.md b/docs/mcp-usage.md new file mode 100644 index 0000000..fa50a39 --- /dev/null +++ b/docs/mcp-usage.md @@ -0,0 +1,115 @@ +# MCP 协议物联网控制用法说明 + +> 本文档介绍如何基于 MCP 协议实现 ESP32 设备的物联网控制。详细协议流程请参考 [`mcp-protocol.md`](./mcp-protocol.md)。 + +## 简介 + +MCP(Model Context Protocol)是新一代推荐用于物联网控制的协议,通过标准 JSON-RPC 2.0 格式在后台与设备间发现和调用"工具"(Tool),实现灵活的设备控制。 + +## 典型使用流程 + +1. 设备启动后通过基础协议(如 WebSocket/MQTT)与后台建立连接。 +2. 后台通过 MCP 协议的 `initialize` 方法初始化会话。 +3. 后台通过 `tools/list` 获取设备支持的所有工具(功能)及参数说明。 +4. 后台通过 `tools/call` 调用具体工具,实现对设备的控制。 + +详细协议格式与交互请见 [`mcp-protocol.md`](./mcp-protocol.md)。 + +## 设备端工具注册方法说明 + +设备通过 `McpServer::AddTool` 方法注册可被后台调用的"工具"。其常用函数签名如下: + +```cpp +void AddTool( + const std::string& name, // 工具名称,建议唯一且有层次感,如 self.dog.forward + const std::string& description, // 工具描述,简明说明功能,便于大模型理解 + const PropertyList& properties, // 输入参数列表(可为空),支持类型:布尔、整数、字符串 + std::function callback // 工具被调用时的回调实现 +); +``` +- name:工具唯一标识,建议用"模块.功能"命名风格。 +- description:自然语言描述,便于 AI/用户理解。 +- properties:参数列表,支持类型有布尔、整数、字符串,可指定范围和默认值。 +- callback:收到调用请求时的实际执行逻辑,返回值可为 bool/int/string。 + +## 典型注册示例(以 ESP-Hi 为例) + +```cpp +void InitializeTools() { + auto& mcp_server = McpServer::GetInstance(); + // 例1:无参数,控制机器人前进 + mcp_server.AddTool("self.dog.forward", "机器人向前移动", PropertyList(), [this](const PropertyList&) -> ReturnValue { + servo_dog_ctrl_send(DOG_STATE_FORWARD, NULL); + return true; + }); + // 例2:带参数,设置灯光 RGB 颜色 + mcp_server.AddTool("self.light.set_rgb", "设置RGB颜色", PropertyList({ + Property("r", kPropertyTypeInteger, 0, 255), + Property("g", kPropertyTypeInteger, 0, 255), + Property("b", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int r = properties["r"].value(); + int g = properties["g"].value(); + int b = properties["b"].value(); + led_on_ = true; + SetLedColor(r, g, b); + return true; + }); +} +``` + +## 常见工具调用 JSON-RPC 示例 + +### 1. 获取工具列表 +```json +{ + "jsonrpc": "2.0", + "method": "tools/list", + "params": { "cursor": "" }, + "id": 1 +} +``` + +### 2. 控制底盘前进 +```json +{ + "jsonrpc": "2.0", + "method": "tools/call", + "params": { + "name": "self.chassis.go_forward", + "arguments": {} + }, + "id": 2 +} +``` + +### 3. 切换灯光模式 +```json +{ + "jsonrpc": "2.0", + "method": "tools/call", + "params": { + "name": "self.chassis.switch_light_mode", + "arguments": { "light_mode": 3 } + }, + "id": 3 +} +``` + +### 4. 摄像头翻转 +```json +{ + "jsonrpc": "2.0", + "method": "tools/call", + "params": { + "name": "self.camera.set_camera_flipped", + "arguments": {} + }, + "id": 4 +} +``` + +## 备注 +- 工具名称、参数及返回值请以设备端 `AddTool` 注册为准。 +- 推荐所有新项目统一采用 MCP 协议进行物联网控制。 +- 详细协议与进阶用法请查阅 [`mcp-protocol.md`](./mcp-protocol.md)。 \ No newline at end of file diff --git a/docs/mqtt-udp.md b/docs/mqtt-udp.md new file mode 100644 index 0000000..478e466 --- /dev/null +++ b/docs/mqtt-udp.md @@ -0,0 +1,393 @@ +# MQTT + UDP 混合通信协议文档 + +基于代码实现整理的 MQTT + UDP 混合通信协议文档,概述设备端与服务器之间如何通过 MQTT 进行控制消息传输,通过 UDP 进行音频数据传输的交互方式。 + +--- + +## 1. 协议概览 + +本协议采用混合传输方式: +- **MQTT**:用于控制消息、状态同步、JSON 数据交换 +- **UDP**:用于实时音频数据传输,支持加密 + +### 1.1 协议特点 + +- **双通道设计**:控制与数据分离,确保实时性 +- **加密传输**:UDP 音频数据使用 AES-CTR 加密 +- **序列号保护**:防止数据包重放和乱序 +- **自动重连**:MQTT 连接断开时自动重连 + +--- + +## 2. 总体流程概览 + +```mermaid +sequenceDiagram + participant Device as ESP32 设备 + participant MQTT as MQTT 服务器 + participant UDP as UDP 服务器 + + Note over Device, UDP: 1. 建立 MQTT 连接 + Device->>MQTT: MQTT Connect + MQTT->>Device: Connected + + Note over Device, UDP: 2. 请求音频通道 + Device->>MQTT: Hello Message (type: "hello", transport: "udp") + MQTT->>Device: Hello Response (UDP 连接信息 + 加密密钥) + + Note over Device, UDP: 3. 建立 UDP 连接 + Device->>UDP: UDP Connect + UDP->>Device: Connected + + Note over Device, UDP: 4. 音频数据传输 + loop 音频流传输 + Device->>UDP: 加密音频数据 (Opus) + UDP->>Device: 加密音频数据 (Opus) + end + + Note over Device, UDP: 5. 控制消息交换 + par 控制消息 + Device->>MQTT: Listen/TTS/MCP 消息 + MQTT->>Device: STT/TTS/MCP 响应 + end + + Note over Device, UDP: 6. 关闭连接 + Device->>MQTT: Goodbye Message + Device->>UDP: Disconnect +``` + +--- + +## 3. MQTT 控制通道 + +### 3.1 连接建立 + +设备通过 MQTT 连接到服务器,连接参数包括: +- **Endpoint**:MQTT 服务器地址和端口 +- **Client ID**:设备唯一标识符 +- **Username/Password**:认证凭据 +- **Keep Alive**:心跳间隔(默认240秒) + +### 3.2 Hello 消息交换 + +#### 3.2.1 设备端发送 Hello + +```json +{ + "type": "hello", + "version": 3, + "transport": "udp", + "features": { + "mcp": true + }, + "audio_params": { + "format": "opus", + "sample_rate": 16000, + "channels": 1, + "frame_duration": 60 + } +} +``` + +#### 3.2.2 服务器响应 Hello + +```json +{ + "type": "hello", + "transport": "udp", + "session_id": "xxx", + "audio_params": { + "format": "opus", + "sample_rate": 24000, + "channels": 1, + "frame_duration": 60 + }, + "udp": { + "server": "192.168.1.100", + "port": 8888, + "key": "0123456789ABCDEF0123456789ABCDEF", + "nonce": "0123456789ABCDEF0123456789ABCDEF" + } +} +``` + +**字段说明:** +- `udp.server`:UDP 服务器地址 +- `udp.port`:UDP 服务器端口 +- `udp.key`:AES 加密密钥(十六进制字符串) +- `udp.nonce`:AES 加密随机数(十六进制字符串) + +### 3.3 JSON 消息类型 + +#### 3.3.1 设备端→服务器 + +1. **Listen 消息** + ```json + { + "session_id": "xxx", + "type": "listen", + "state": "start", + "mode": "manual" + } + ``` + +2. **Abort 消息** + ```json + { + "session_id": "xxx", + "type": "abort", + "reason": "wake_word_detected" + } + ``` + +3. **MCP 消息** + ```json + { + "session_id": "xxx", + "type": "mcp", + "payload": { + "jsonrpc": "2.0", + "id": 1, + "result": {...} + } + } + ``` + +4. **Goodbye 消息** + ```json + { + "session_id": "xxx", + "type": "goodbye" + } + ``` + +#### 3.3.2 服务器→设备端 + +支持的消息类型与 WebSocket 协议一致,包括: +- **STT**:语音识别结果 +- **TTS**:语音合成控制 +- **LLM**:情感表达控制 +- **MCP**:物联网控制 +- **System**:系统控制 +- **Custom**:自定义消息(可选) + +--- + +## 4. UDP 音频通道 + +### 4.1 连接建立 + +设备收到 MQTT Hello 响应后,使用其中的 UDP 连接信息建立音频通道: +1. 解析 UDP 服务器地址和端口 +2. 解析加密密钥和随机数 +3. 初始化 AES-CTR 加密上下文 +4. 建立 UDP 连接 + +### 4.2 音频数据格式 + +#### 4.2.1 加密音频包结构 + +``` +|type 1byte|flags 1byte|payload_len 2bytes|ssrc 4bytes|timestamp 4bytes|sequence 4bytes| +|payload payload_len bytes| +``` + +**字段说明:** +- `type`:数据包类型,固定为 0x01 +- `flags`:标志位,当前未使用 +- `payload_len`:负载长度(网络字节序) +- `ssrc`:同步源标识符 +- `timestamp`:时间戳(网络字节序) +- `sequence`:序列号(网络字节序) +- `payload`:加密的 Opus 音频数据 + +#### 4.2.2 加密算法 + +使用 **AES-CTR** 模式加密: +- **密钥**:128位,由服务器提供 +- **随机数**:128位,由服务器提供 +- **计数器**:包含时间戳和序列号信息 + +### 4.3 序列号管理 + +- **发送端**:`local_sequence_` 单调递增 +- **接收端**:`remote_sequence_` 验证连续性 +- **防重放**:拒绝序列号小于期望值的数据包 +- **容错处理**:允许轻微的序列号跳跃,记录警告 + +### 4.4 错误处理 + +1. **解密失败**:记录错误,丢弃数据包 +2. **序列号异常**:记录警告,但仍处理数据包 +3. **数据包格式错误**:记录错误,丢弃数据包 + +--- + +## 5. 状态管理 + +### 5.1 连接状态 + +```mermaid +stateDiagram + direction TB + [*] --> Disconnected + Disconnected --> MqttConnecting: StartMqttClient() + MqttConnecting --> MqttConnected: MQTT Connected + MqttConnecting --> Disconnected: Connect Failed + MqttConnected --> RequestingChannel: OpenAudioChannel() + RequestingChannel --> ChannelOpened: Hello Exchange Success + RequestingChannel --> MqttConnected: Hello Timeout/Failed + ChannelOpened --> UdpConnected: UDP Connect Success + UdpConnected --> AudioStreaming: Start Audio Transfer + AudioStreaming --> UdpConnected: Stop Audio Transfer + UdpConnected --> ChannelOpened: UDP Disconnect + ChannelOpened --> MqttConnected: CloseAudioChannel() + MqttConnected --> Disconnected: MQTT Disconnect +``` + +### 5.2 状态检查 + +设备通过以下条件判断音频通道是否可用: +```cpp +bool IsAudioChannelOpened() const { + return udp_ != nullptr && !error_occurred_ && !IsTimeout(); +} +``` + +--- + +## 6. 配置参数 + +### 6.1 MQTT 配置 + +从设置中读取的配置项: +- `endpoint`:MQTT 服务器地址 +- `client_id`:客户端标识符 +- `username`:用户名 +- `password`:密码 +- `keepalive`:心跳间隔(默认240秒) +- `publish_topic`:发布主题 + +### 6.2 音频参数 + +- **格式**:Opus +- **采样率**:16000 Hz(设备端)/ 24000 Hz(服务器端) +- **声道数**:1(单声道) +- **帧时长**:60ms + +--- + +## 7. 错误处理与重连 + +### 7.1 MQTT 重连机制 + +- 连接失败时自动重试 +- 支持错误上报控制 +- 断线时触发清理流程 + +### 7.2 UDP 连接管理 + +- 连接失败时不自动重试 +- 依赖 MQTT 通道重新协商 +- 支持连接状态查询 + +### 7.3 超时处理 + +基类 `Protocol` 提供超时检测: +- 默认超时时间:120 秒 +- 基于最后接收时间计算 +- 超时时自动标记为不可用 + +--- + +## 8. 安全考虑 + +### 8.1 传输加密 + +- **MQTT**:支持 TLS/SSL 加密(端口8883) +- **UDP**:使用 AES-CTR 加密音频数据 + +### 8.2 认证机制 + +- **MQTT**:用户名/密码认证 +- **UDP**:通过 MQTT 通道分发密钥 + +### 8.3 防重放攻击 + +- 序列号单调递增 +- 拒绝过期数据包 +- 时间戳验证 + +--- + +## 9. 性能优化 + +### 9.1 并发控制 + +使用互斥锁保护 UDP 连接: +```cpp +std::lock_guard lock(channel_mutex_); +``` + +### 9.2 内存管理 + +- 动态创建/销毁网络对象 +- 智能指针管理音频数据包 +- 及时释放加密上下文 + +### 9.3 网络优化 + +- UDP 连接复用 +- 数据包大小优化 +- 序列号连续性检查 + +--- + +## 10. 与 WebSocket 协议的比较 + +| 特性 | MQTT + UDP | WebSocket | +|------|------------|-----------| +| 控制通道 | MQTT | WebSocket | +| 音频通道 | UDP (加密) | WebSocket (二进制) | +| 实时性 | 高 (UDP) | 中等 | +| 可靠性 | 中等 | 高 | +| 复杂度 | 高 | 低 | +| 加密 | AES-CTR | TLS | +| 防火墙友好度 | 低 | 高 | + +--- + +## 11. 部署建议 + +### 11.1 网络环境 + +- 确保 UDP 端口可达 +- 配置防火墙规则 +- 考虑 NAT 穿透 + +### 11.2 服务器配置 + +- MQTT Broker 配置 +- UDP 服务器部署 +- 密钥管理系统 + +### 11.3 监控指标 + +- 连接成功率 +- 音频传输延迟 +- 数据包丢失率 +- 解密失败率 + +--- + +## 12. 总结 + +MQTT + UDP 混合协议通过以下设计实现高效的音视频通信: + +- **分离式架构**:控制与数据通道分离,各司其职 +- **加密保护**:AES-CTR 确保音频数据安全传输 +- **序列化管理**:防止重放攻击和数据乱序 +- **自动恢复**:支持连接断开后的自动重连 +- **性能优化**:UDP 传输保证音频数据的实时性 + +该协议适用于对实时性要求较高的语音交互场景,但需要在网络复杂度和传输性能之间做出权衡。 \ No newline at end of file diff --git a/docs/v0/AtomMatrix-echo-base.jpg b/docs/v0/AtomMatrix-echo-base.jpg new file mode 100644 index 0000000..979cf81 Binary files /dev/null and b/docs/v0/AtomMatrix-echo-base.jpg differ diff --git a/docs/v0/ESP32-BreadBoard.jpg b/docs/v0/ESP32-BreadBoard.jpg new file mode 100644 index 0000000..f7a6fd4 Binary files /dev/null and b/docs/v0/ESP32-BreadBoard.jpg differ diff --git a/docs/v0/atoms3r-echo-base.jpg b/docs/v0/atoms3r-echo-base.jpg new file mode 100755 index 0000000..961e72b Binary files /dev/null and b/docs/v0/atoms3r-echo-base.jpg differ diff --git a/docs/v0/esp32s3-box3.jpg b/docs/v0/esp32s3-box3.jpg new file mode 100644 index 0000000..53c4b55 Binary files /dev/null and b/docs/v0/esp32s3-box3.jpg differ diff --git a/docs/v0/lichuang-s3.jpg b/docs/v0/lichuang-s3.jpg new file mode 100644 index 0000000..721e0a0 Binary files /dev/null and b/docs/v0/lichuang-s3.jpg differ diff --git a/docs/v0/m5stack-cores3.jpg b/docs/v0/m5stack-cores3.jpg new file mode 100644 index 0000000..b123f73 Binary files /dev/null and b/docs/v0/m5stack-cores3.jpg differ diff --git a/docs/v0/magiclick-2p4.jpg b/docs/v0/magiclick-2p4.jpg new file mode 100644 index 0000000..beffb3d Binary files /dev/null and b/docs/v0/magiclick-2p4.jpg differ diff --git a/docs/v0/waveshare-esp32-s3-touch-amoled-1.8.jpg b/docs/v0/waveshare-esp32-s3-touch-amoled-1.8.jpg new file mode 100644 index 0000000..90f2744 Binary files /dev/null and b/docs/v0/waveshare-esp32-s3-touch-amoled-1.8.jpg differ diff --git a/docs/v0/wiring.jpg b/docs/v0/wiring.jpg new file mode 100644 index 0000000..764c170 Binary files /dev/null and b/docs/v0/wiring.jpg differ diff --git a/docs/v1/atoms3r.jpg b/docs/v1/atoms3r.jpg new file mode 100644 index 0000000..45cbb45 Binary files /dev/null and b/docs/v1/atoms3r.jpg differ diff --git a/docs/v1/electron-bot.png b/docs/v1/electron-bot.png new file mode 100644 index 0000000..4d00d6d Binary files /dev/null and b/docs/v1/electron-bot.png differ diff --git a/docs/v1/esp-hi.jpg b/docs/v1/esp-hi.jpg new file mode 100644 index 0000000..d6fc714 Binary files /dev/null and b/docs/v1/esp-hi.jpg differ diff --git a/docs/v1/esp-sparkbot.jpg b/docs/v1/esp-sparkbot.jpg new file mode 100644 index 0000000..b738840 Binary files /dev/null and b/docs/v1/esp-sparkbot.jpg differ diff --git a/docs/v1/espbox3.jpg b/docs/v1/espbox3.jpg new file mode 100644 index 0000000..641d74b Binary files /dev/null and b/docs/v1/espbox3.jpg differ diff --git a/docs/v1/lichuang-s3.jpg b/docs/v1/lichuang-s3.jpg new file mode 100644 index 0000000..a559070 Binary files /dev/null and b/docs/v1/lichuang-s3.jpg differ diff --git a/docs/v1/lilygo-t-circle-s3.jpg b/docs/v1/lilygo-t-circle-s3.jpg new file mode 100644 index 0000000..45985d8 Binary files /dev/null and b/docs/v1/lilygo-t-circle-s3.jpg differ diff --git a/docs/v1/m5cores3.jpg b/docs/v1/m5cores3.jpg new file mode 100644 index 0000000..6a30cef Binary files /dev/null and b/docs/v1/m5cores3.jpg differ diff --git a/docs/v1/magiclick.jpg b/docs/v1/magiclick.jpg new file mode 100644 index 0000000..3c01463 Binary files /dev/null and b/docs/v1/magiclick.jpg differ diff --git a/docs/v1/movecall-cuican-esp32s3.jpg b/docs/v1/movecall-cuican-esp32s3.jpg new file mode 100755 index 0000000..ae70cfd Binary files /dev/null and b/docs/v1/movecall-cuican-esp32s3.jpg differ diff --git a/docs/v1/movecall-moji-esp32s3.jpg b/docs/v1/movecall-moji-esp32s3.jpg new file mode 100644 index 0000000..dec4526 Binary files /dev/null and b/docs/v1/movecall-moji-esp32s3.jpg differ diff --git a/docs/v1/otto-robot.png b/docs/v1/otto-robot.png new file mode 100644 index 0000000..d61cbdc Binary files /dev/null and b/docs/v1/otto-robot.png differ diff --git a/docs/v1/sensecap_watcher.jpg b/docs/v1/sensecap_watcher.jpg new file mode 100644 index 0000000..b1d7e4c Binary files /dev/null and b/docs/v1/sensecap_watcher.jpg differ diff --git a/docs/v1/waveshare.jpg b/docs/v1/waveshare.jpg new file mode 100644 index 0000000..7dacf2f Binary files /dev/null and b/docs/v1/waveshare.jpg differ diff --git a/docs/v1/wiring2.jpg b/docs/v1/wiring2.jpg new file mode 100644 index 0000000..f3a67ae Binary files /dev/null and b/docs/v1/wiring2.jpg differ diff --git a/docs/v1/wmnologo_xingzhi_0.96.jpg b/docs/v1/wmnologo_xingzhi_0.96.jpg new file mode 100644 index 0000000..24369cc Binary files /dev/null and b/docs/v1/wmnologo_xingzhi_0.96.jpg differ diff --git a/docs/v1/wmnologo_xingzhi_1.54.jpg b/docs/v1/wmnologo_xingzhi_1.54.jpg new file mode 100644 index 0000000..7456477 Binary files /dev/null and b/docs/v1/wmnologo_xingzhi_1.54.jpg differ diff --git a/docs/v1/xmini-c3.jpg b/docs/v1/xmini-c3.jpg new file mode 100644 index 0000000..f1ed8c2 Binary files /dev/null and b/docs/v1/xmini-c3.jpg differ diff --git a/docs/websocket.md b/docs/websocket.md new file mode 100644 index 0000000..f767114 --- /dev/null +++ b/docs/websocket.md @@ -0,0 +1,495 @@ +以下是一份基于代码实现整理的 WebSocket 通信协议文档,概述设备端与服务器之间如何通过 WebSocket 进行交互。 + +该文档仅基于所提供的代码推断,实际部署时可能需要结合服务器端实现进行进一步确认或补充。 + +--- + +## 1. 总体流程概览 + +1. **设备端初始化** + - 设备上电、初始化 `Application`: + - 初始化音频编解码器、显示屏、LED 等 + - 连接网络 + - 创建并初始化实现 `Protocol` 接口的 WebSocket 协议实例(`WebsocketProtocol`) + - 进入主循环等待事件(音频输入、音频输出、调度任务等)。 + +2. **建立 WebSocket 连接** + - 当设备需要开始语音会话时(例如用户唤醒、手动按键触发等),调用 `OpenAudioChannel()`: + - 根据配置获取 WebSocket URL + - 设置若干请求头(`Authorization`, `Protocol-Version`, `Device-Id`, `Client-Id`) + - 调用 `Connect()` 与服务器建立 WebSocket 连接 + +3. **设备端发送 "hello" 消息** + - 连接成功后,设备会发送一条 JSON 消息,示例结构如下: + ```json + { + "type": "hello", + "version": 1, + "features": { + "mcp": true + }, + "transport": "websocket", + "audio_params": { + "format": "opus", + "sample_rate": 16000, + "channels": 1, + "frame_duration": 60 + } + } + ``` + - 其中 `features` 字段为可选,内容根据设备编译配置自动生成。例如:`"mcp": true` 表示支持 MCP 协议。 + - `frame_duration` 的值对应 `OPUS_FRAME_DURATION_MS`(例如 60ms)。 + +4. **服务器回复 "hello"** + - 设备等待服务器返回一条包含 `"type": "hello"` 的 JSON 消息,并检查 `"transport": "websocket"` 是否匹配。 + - 服务器可选下发 `session_id` 字段,设备端收到后会自动记录。 + - 示例: + ```json + { + "type": "hello", + "transport": "websocket", + "session_id": "xxx", + "audio_params": { + "format": "opus", + "sample_rate": 24000, + "channels": 1, + "frame_duration": 60 + } + } + ``` + - 如果匹配,则认为服务器已就绪,标记音频通道打开成功。 + - 如果在超时时间(默认 10 秒)内未收到正确回复,认为连接失败并触发网络错误回调。 + +5. **后续消息交互** + - 设备端和服务器端之间可发送两种主要类型的数据: + 1. **二进制音频数据**(Opus 编码) + 2. **文本 JSON 消息**(用于传输聊天状态、TTS/STT 事件、MCP 协议消息等) + + - 在代码里,接收回调主要分为: + - `OnData(...)`: + - 当 `binary` 为 `true` 时,认为是音频帧;设备会将其当作 Opus 数据进行解码。 + - 当 `binary` 为 `false` 时,认为是 JSON 文本,需要在设备端用 cJSON 进行解析并做相应业务逻辑处理(如聊天、TTS、MCP 协议消息等)。 + + - 当服务器或网络出现断连,回调 `OnDisconnected()` 被触发: + - 设备会调用 `on_audio_channel_closed_()`,并最终回到空闲状态。 + +6. **关闭 WebSocket 连接** + - 设备在需要结束语音会话时,会调用 `CloseAudioChannel()` 主动断开连接,并回到空闲状态。 + - 或者如果服务器端主动断开,也会引发同样的回调流程。 + +--- + +## 2. 通用请求头 + +在建立 WebSocket 连接时,代码示例中设置了以下请求头: + +- `Authorization`: 用于存放访问令牌,形如 `"Bearer "` +- `Protocol-Version`: 协议版本号,与 hello 消息体内的 `version` 字段保持一致 +- `Device-Id`: 设备物理网卡 MAC 地址 +- `Client-Id`: 软件生成的 UUID(擦除 NVS 或重新烧录完整固件会重置) + +这些头会随着 WebSocket 握手一起发送到服务器,服务器可根据需求进行校验、认证等。 + +--- + +## 3. 二进制协议版本 + +设备支持多种二进制协议版本,通过配置中的 `version` 字段指定: + +### 3.1 版本1(默认) +直接发送 Opus 音频数据,无额外元数据。Websocket 协议会区分 text 与 binary。 + +### 3.2 版本2 +使用 `BinaryProtocol2` 结构: +```c +struct BinaryProtocol2 { + uint16_t version; // 协议版本 + uint16_t type; // 消息类型 (0: OPUS, 1: JSON) + uint32_t reserved; // 保留字段 + uint32_t timestamp; // 时间戳(毫秒,用于服务器端AEC) + uint32_t payload_size; // 负载大小(字节) + uint8_t payload[]; // 负载数据 +} __attribute__((packed)); +``` + +### 3.3 版本3 +使用 `BinaryProtocol3` 结构: +```c +struct BinaryProtocol3 { + uint8_t type; // 消息类型 + uint8_t reserved; // 保留字段 + uint16_t payload_size; // 负载大小 + uint8_t payload[]; // 负载数据 +} __attribute__((packed)); +``` + +--- + +## 4. JSON 消息结构 + +WebSocket 文本帧以 JSON 方式传输,以下为常见的 `"type"` 字段及其对应业务逻辑。若消息里包含未列出的字段,可能为可选或特定实现细节。 + +### 4.1 设备端→服务器 + +1. **Hello** + - 连接成功后,由设备端发送,告知服务器基本参数。 + - 例: + ```json + { + "type": "hello", + "version": 1, + "features": { + "mcp": true + }, + "transport": "websocket", + "audio_params": { + "format": "opus", + "sample_rate": 16000, + "channels": 1, + "frame_duration": 60 + } + } + ``` + +2. **Listen** + - 表示设备端开始或停止录音监听。 + - 常见字段: + - `"session_id"`:会话标识 + - `"type": "listen"` + - `"state"`:`"start"`, `"stop"`, `"detect"`(唤醒检测已触发) + - `"mode"`:`"auto"`, `"manual"` 或 `"realtime"`,表示识别模式。 + - 例:开始监听 + ```json + { + "session_id": "xxx", + "type": "listen", + "state": "start", + "mode": "manual" + } + ``` + +3. **Abort** + - 终止当前说话(TTS 播放)或语音通道。 + - 例: + ```json + { + "session_id": "xxx", + "type": "abort", + "reason": "wake_word_detected" + } + ``` + - `reason` 值可为 `"wake_word_detected"` 或其他。 + +4. **Wake Word Detected** + - 用于设备端向服务器告知检测到唤醒词。 + - 在发送该消息之前,可提前发送唤醒词的 Opus 音频数据,用于服务器进行声纹检测。 + - 例: + ```json + { + "session_id": "xxx", + "type": "listen", + "state": "detect", + "text": "你好小明" + } + ``` + +5. **MCP** + - 推荐用于物联网控制的新一代协议。所有设备能力发现、工具调用等均通过 type: "mcp" 的消息进行,payload 内部为标准 JSON-RPC 2.0(详见 [MCP 协议文档](./mcp-protocol.md))。 + + - **设备端到服务器发送 result 的例子:** + ```json + { + "session_id": "xxx", + "type": "mcp", + "payload": { + "jsonrpc": "2.0", + "id": 1, + "result": { + "content": [ + { "type": "text", "text": "true" } + ], + "isError": false + } + } + } + ``` + +--- + +### 4.2 服务器→设备端 + +1. **Hello** + - 服务器端返回的握手确认消息。 + - 必须包含 `"type": "hello"` 和 `"transport": "websocket"`。 + - 可能会带有 `audio_params`,表示服务器期望的音频参数,或与设备端对齐的配置。 + - 服务器可选下发 `session_id` 字段,设备端收到后会自动记录。 + - 成功接收后设备端会设置事件标志,表示 WebSocket 通道就绪。 + +2. **STT** + - `{"session_id": "xxx", "type": "stt", "text": "..."}` + - 表示服务器端识别到了用户语音。(例如语音转文本结果) + - 设备可能将此文本显示到屏幕上,后续再进入回答等流程。 + +3. **LLM** + - `{"session_id": "xxx", "type": "llm", "emotion": "happy", "text": "😀"}` + - 服务器指示设备调整表情动画 / UI 表达。 + +4. **TTS** + - `{"session_id": "xxx", "type": "tts", "state": "start"}`:服务器准备下发 TTS 音频,设备端进入 "speaking" 播放状态。 + - `{"session_id": "xxx", "type": "tts", "state": "stop"}`:表示本次 TTS 结束。 + - `{"session_id": "xxx", "type": "tts", "state": "sentence_start", "text": "..."}` + - 让设备在界面上显示当前要播放或朗读的文本片段(例如用于显示给用户)。 + +5. **MCP** + - 服务器通过 type: "mcp" 的消息下发物联网相关的控制指令或返回调用结果,payload 结构同上。 + + - **服务器到设备端发送 tools/call 的例子:** + ```json + { + "session_id": "xxx", + "type": "mcp", + "payload": { + "jsonrpc": "2.0", + "method": "tools/call", + "params": { + "name": "self.light.set_rgb", + "arguments": { "r": 255, "g": 0, "b": 0 } + }, + "id": 1 + } + } + ``` + +6. **System** + - 系统控制命令,常用于远程升级更新。 + - 例: + ```json + { + "session_id": "xxx", + "type": "system", + "command": "reboot" + } + ``` + - 支持的命令: + - `"reboot"`:重启设备 + +7. **Custom**(可选) + - 自定义消息,当 `CONFIG_RECEIVE_CUSTOM_MESSAGE` 启用时支持。 + - 例: + ```json + { + "session_id": "xxx", + "type": "custom", + "payload": { + "message": "自定义内容" + } + } + ``` + +8. **音频数据:二进制帧** + - 当服务器发送音频二进制帧(Opus 编码)时,设备端解码并播放。 + - 若设备端正在处于 "listening" (录音)状态,收到的音频帧会被忽略或清空以防冲突。 + +--- + +## 5. 音频编解码 + +1. **设备端发送录音数据** + - 音频输入经过可能的回声消除、降噪或音量增益后,通过 Opus 编码打包为二进制帧发送给服务器。 + - 根据协议版本,可能直接发送 Opus 数据(版本1)或使用带元数据的二进制协议(版本2/3)。 + +2. **设备端播放收到的音频** + - 收到服务器的二进制帧时,同样认定是 Opus 数据。 + - 设备端会进行解码,然后交由音频输出接口播放。 + - 如果服务器的音频采样率与设备不一致,会在解码后再进行重采样。 + +--- + +## 6. 常见状态流转 + +以下为常见设备端关键状态流转,与 WebSocket 消息对应: + +1. **Idle** → **Connecting** + - 用户触发或唤醒后,设备调用 `OpenAudioChannel()` → 建立 WebSocket 连接 → 发送 `"type":"hello"`。 + +2. **Connecting** → **Listening** + - 成功建立连接后,若继续执行 `SendStartListening(...)`,则进入录音状态。此时设备会持续编码麦克风数据并发送到服务器。 + +3. **Listening** → **Speaking** + - 收到服务器 TTS Start 消息 (`{"type":"tts","state":"start"}`) → 停止录音并播放接收到的音频。 + +4. **Speaking** → **Idle** + - 服务器 TTS Stop (`{"type":"tts","state":"stop"}`) → 音频播放结束。若未继续进入自动监听,则返回 Idle;如果配置了自动循环,则再度进入 Listening。 + +5. **Listening** / **Speaking** → **Idle**(遇到异常或主动中断) + - 调用 `SendAbortSpeaking(...)` 或 `CloseAudioChannel()` → 中断会话 → 关闭 WebSocket → 状态回到 Idle。 + +### 自动模式状态流转图 + +```mermaid +stateDiagram + direction TB + [*] --> kDeviceStateUnknown + kDeviceStateUnknown --> kDeviceStateStarting:初始化 + kDeviceStateStarting --> kDeviceStateWifiConfiguring:配置WiFi + kDeviceStateStarting --> kDeviceStateActivating:激活设备 + kDeviceStateActivating --> kDeviceStateUpgrading:检测到新版本 + kDeviceStateActivating --> kDeviceStateIdle:激活完成 + kDeviceStateIdle --> kDeviceStateConnecting:开始连接 + kDeviceStateConnecting --> kDeviceStateIdle:连接失败 + kDeviceStateConnecting --> kDeviceStateListening:连接成功 + kDeviceStateListening --> kDeviceStateSpeaking:开始说话 + kDeviceStateSpeaking --> kDeviceStateListening:结束说话 + kDeviceStateListening --> kDeviceStateIdle:手动终止 + kDeviceStateSpeaking --> kDeviceStateIdle:自动终止 +``` + +### 手动模式状态流转图 + +```mermaid +stateDiagram + direction TB + [*] --> kDeviceStateUnknown + kDeviceStateUnknown --> kDeviceStateStarting:初始化 + kDeviceStateStarting --> kDeviceStateWifiConfiguring:配置WiFi + kDeviceStateStarting --> kDeviceStateActivating:激活设备 + kDeviceStateActivating --> kDeviceStateUpgrading:检测到新版本 + kDeviceStateActivating --> kDeviceStateIdle:激活完成 + kDeviceStateIdle --> kDeviceStateConnecting:开始连接 + kDeviceStateConnecting --> kDeviceStateIdle:连接失败 + kDeviceStateConnecting --> kDeviceStateListening:连接成功 + kDeviceStateIdle --> kDeviceStateListening:开始监听 + kDeviceStateListening --> kDeviceStateIdle:停止监听 + kDeviceStateIdle --> kDeviceStateSpeaking:开始说话 + kDeviceStateSpeaking --> kDeviceStateIdle:结束说话 +``` + +--- + +## 7. 错误处理 + +1. **连接失败** + - 如果 `Connect(url)` 返回失败或在等待服务器 "hello" 消息时超时,触发 `on_network_error_()` 回调。设备会提示"无法连接到服务"或类似错误信息。 + +2. **服务器断开** + - 如果 WebSocket 异常断开,回调 `OnDisconnected()`: + - 设备回调 `on_audio_channel_closed_()` + - 切换到 Idle 或其他重试逻辑。 + +--- + +## 8. 其它注意事项 + +1. **鉴权** + - 设备通过设置 `Authorization: Bearer ` 提供鉴权,服务器端需验证是否有效。 + - 如果令牌过期或无效,服务器可拒绝握手或在后续断开。 + +2. **会话控制** + - 代码中部分消息包含 `session_id`,用于区分独立的对话或操作。服务端可根据需要对不同会话做分离处理。 + +3. **音频负载** + - 代码里默认使用 Opus 格式,并设置 `sample_rate = 16000`,单声道。帧时长由 `OPUS_FRAME_DURATION_MS` 控制,一般为 60ms。可根据带宽或性能做适当调整。为了获得更好的音乐播放效果,服务器下行音频可能使用 24000 采样率。 + +4. **协议版本配置** + - 通过设置中的 `version` 字段配置二进制协议版本(1、2 或 3) + - 版本1:直接发送 Opus 数据 + - 版本2:使用带时间戳的二进制协议,适用于服务器端 AEC + - 版本3:使用简化的二进制协议 + +5. **物联网控制推荐 MCP 协议** + - 设备与服务器之间的物联网能力发现、状态同步、控制指令等,建议全部通过 MCP 协议(type: "mcp")实现。原有的 type: "iot" 方案已废弃。 + - MCP 协议可在 WebSocket、MQTT 等多种底层协议上传输,具备更好的扩展性和标准化能力。 + - 详细用法请参考 [MCP 协议文档](./mcp-protocol.md) 及 [MCP 物联网控制用法](./mcp-usage.md)。 + +6. **错误或异常 JSON** + - 当 JSON 中缺少必要字段,例如 `{"type": ...}`,设备端会记录错误日志(`ESP_LOGE(TAG, "Missing message type, data: %s", data);`),不会执行任何业务。 + +--- + +## 9. 消息示例 + +下面给出一个典型的双向消息示例(流程简化示意): + +1. **设备端 → 服务器**(握手) + ```json + { + "type": "hello", + "version": 1, + "features": { + "mcp": true + }, + "transport": "websocket", + "audio_params": { + "format": "opus", + "sample_rate": 16000, + "channels": 1, + "frame_duration": 60 + } + } + ``` + +2. **服务器 → 设备端**(握手应答) + ```json + { + "type": "hello", + "transport": "websocket", + "session_id": "xxx", + "audio_params": { + "format": "opus", + "sample_rate": 16000 + } + } + ``` + +3. **设备端 → 服务器**(开始监听) + ```json + { + "session_id": "xxx", + "type": "listen", + "state": "start", + "mode": "auto" + } + ``` + 同时设备端开始发送二进制帧(Opus 数据)。 + +4. **服务器 → 设备端**(ASR 结果) + ```json + { + "session_id": "xxx", + "type": "stt", + "text": "用户说的话" + } + ``` + +5. **服务器 → 设备端**(TTS开始) + ```json + { + "session_id": "xxx", + "type": "tts", + "state": "start" + } + ``` + 接着服务器发送二进制音频帧给设备端播放。 + +6. **服务器 → 设备端**(TTS结束) + ```json + { + "session_id": "xxx", + "type": "tts", + "state": "stop" + } + ``` + 设备端停止播放音频,若无更多指令,则回到空闲状态。 + +--- + +## 10. 总结 + +本协议通过在 WebSocket 上层传输 JSON 文本与二进制音频帧,完成功能包括音频流上传、TTS 音频播放、语音识别与状态管理、MCP 指令下发等。其核心特征: + +- **握手阶段**:发送 `"type":"hello"`,等待服务器返回。 +- **音频通道**:采用 Opus 编码的二进制帧双向传输语音流,支持多种协议版本。 +- **JSON 消息**:使用 `"type"` 为核心字段标识不同业务逻辑,包括 TTS、STT、MCP、WakeWord、System、Custom 等。 +- **扩展性**:可根据实际需求在 JSON 消息中添加字段,或在 headers 里进行额外鉴权。 + +服务器与设备端需提前约定各类消息的字段含义、时序逻辑以及错误处理规则,方能保证通信顺畅。上述信息可作为基础文档,便于后续对接、开发或扩展。 diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt new file mode 100644 index 0000000..4aef1be --- /dev/null +++ b/main/CMakeLists.txt @@ -0,0 +1,918 @@ +# Define source files +set(SOURCES "audio/audio_codec.cc" + "audio/audio_service.cc" + "audio/codecs/no_audio_codec.cc" + "audio/codecs/box_audio_codec.cc" + "audio/codecs/es8311_audio_codec.cc" + "audio/codecs/es8374_audio_codec.cc" + "audio/codecs/es8388_audio_codec.cc" + "audio/codecs/es8389_audio_codec.cc" + "audio/codecs/dummy_audio_codec.cc" + "audio/processors/audio_debugger.cc" + "led/single_led.cc" + "led/circular_strip.cc" + "led/gpio_led.cc" + "display/display.cc" + "display/lcd_display.cc" + "display/oled_display.cc" + "display/lvgl_display/lvgl_display.cc" + "display/emote_display.cc" + "display/lvgl_display/emoji_collection.cc" + "display/lvgl_display/lvgl_theme.cc" + "display/lvgl_display/lvgl_font.cc" + "display/lvgl_display/lvgl_image.cc" + "display/lvgl_display/gif/lvgl_gif.cc" + "display/lvgl_display/gif/gifdec.c" + "display/lvgl_display/jpg/image_to_jpeg.cpp" + "display/lvgl_display/jpg/jpeg_to_image.c" + "protocols/protocol.cc" + "protocols/mqtt_protocol.cc" + "protocols/websocket_protocol.cc" + "mcp_server.cc" + "system_info.cc" + "application.cc" + "ota.cc" + "settings.cc" + "device_state_event.cc" + "assets.cc" + "main.cc" + "uart_component.cc" + ) + +set(INCLUDE_DIRS "." "display" "display/lvgl_display" "display/lvgl_display/jpg" "audio" "protocols") + +# Add board common files +file(GLOB BOARD_COMMON_SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/boards/common/*.cc) +list(APPEND SOURCES ${BOARD_COMMON_SOURCES}) +list(APPEND INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/boards/common) + +idf_build_get_property(build_components BUILD_COMPONENTS) +# Function to find component dynamically by pattern +function(find_component_by_pattern PATTERN COMPONENT_VAR PATH_VAR) + foreach(COMPONENT ${build_components}) + if(COMPONENT MATCHES "${PATTERN}") + set(${COMPONENT_VAR} ${COMPONENT} PARENT_SCOPE) + idf_component_get_property(COMPONENT_PATH ${COMPONENT} COMPONENT_DIR) + set(${PATH_VAR} "${COMPONENT_PATH}" PARENT_SCOPE) + break() + endif() + endforeach() +endfunction() + +# Set default BUILTIN_TEXT_FONT and BUILTIN_ICON_FONT +set(BUILTIN_TEXT_FONT font_puhui_14_1) +set(BUILTIN_ICON_FONT font_awesome_14_1) + +# Add board files according to BOARD_TYPE +# Set default assets if the board uses partition table V2 +if(CONFIG_BOARD_TYPE_BREAD_COMPACT_WIFI) + set(BOARD_TYPE "bread-compact-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_BREAD_COMPACT_ML307) + set(BOARD_TYPE "bread-compact-ml307") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_BREAD_COMPACT_ESP32) + set(BOARD_TYPE "bread-compact-esp32") +elseif(CONFIG_BOARD_TYPE_BREAD_COMPACT_ESP32_LCD) + set(BOARD_TYPE "bread-compact-esp32-lcd") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_DF_K10) + set(BOARD_TYPE "df-k10") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_DF_S3_AI_CAM) + set(BOARD_TYPE "df-s3-ai-cam") +elseif(CONFIG_BOARD_TYPE_ESP_BOX_3) + set(BOARD_TYPE "esp-box-3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_BOX) + set(BOARD_TYPE "esp-box") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_BOX_LITE) + set(BOARD_TYPE "esp-box-lite") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_KEVIN_BOX_2) + set(BOARD_TYPE "kevin-box-2") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_KEVIN_C3) + set(BOARD_TYPE "kevin-c3") +elseif(CONFIG_BOARD_TYPE_KEVIN_SP_V3_DEV) + set(BOARD_TYPE "kevin-sp-v3-dev") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_KEVIN_SP_V4_DEV) + set(BOARD_TYPE "kevin-sp-v4-dev") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_KEVIN_YUYING_313LCD) + set(BOARD_TYPE "kevin-yuying-313lcd") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LICHUANG_DEV_S3) + set(BOARD_TYPE "lichuang-dev") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LICHUANG_DEV_C3) + set(BOARD_TYPE "lichuang-c3-dev") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_MAGICLICK_S3_2P4) + set(BOARD_TYPE "magiclick-2p4") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_MAGICLICK_S3_2P5) + set(BOARD_TYPE "magiclick-2p5") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_MAGICLICK_C3) + set(BOARD_TYPE "magiclick-c3") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_MAGICLICK_C3_V2) + set(BOARD_TYPE "magiclick-c3-v2") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_M5STACK_CORE_S3) + set(BOARD_TYPE "m5stack-core-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_M5STACK_CORE_TAB5) + set(BOARD_TYPE "m5stack-tab5") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_M5STACK_ATOM_S3_ECHO_BASE) + set(BOARD_TYPE "atoms3-echo-base") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_M5STACK_ATOM_S3R_ECHO_BASE) + set(BOARD_TYPE "atoms3r-echo-base") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_M5STACK_ATOM_S3R_CAM_M12_ECHO_BASE) + set(BOARD_TYPE "atoms3r-cam-m12-echo-base") +elseif(CONFIG_BOARD_TYPE_M5STACK_ATOM_ECHOS3R) + set(BOARD_TYPE "atom-echos3r") +elseif(CONFIG_BOARD_TYPE_M5STACK_ATOM_MATRIX_ECHO_BASE) + set(BOARD_TYPE "atommatrix-echo-base") +elseif(CONFIG_BOARD_TYPE_XMINI_C3_V3) + set(BOARD_TYPE "xmini-c3-v3") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_XMINI_C3_4G) + set(BOARD_TYPE "xmini-c3-4g") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_XMINI_C3) + set(BOARD_TYPE "xmini-c3") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_ESP_KORVO2_V3) + set(BOARD_TYPE "esp32s3-korvo2-v3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_SPARKBOT) + set(BOARD_TYPE "esp-sparkbot") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_SPOT_S3) + set(BOARD_TYPE "esp-spot") +elseif(CONFIG_BOARD_TYPE_ESP_SPOT_C5) + set(BOARD_TYPE "esp-spot") +elseif(CONFIG_BOARD_TYPE_ESP_HI) + set(BOARD_TYPE "esp-hi") + # Set ESP_HI emoji directory for DEFAULT_ASSETS_EXTRA_FILES + set(DEFAULT_ASSETS_EXTRA_FILES "${CMAKE_BINARY_DIR}/emoji") +elseif(CONFIG_BOARD_TYPE_ECHOEAR) + set(BOARD_TYPE "echoear") + set(BUILTIN_TEXT_FONT font_puhui_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_AUDIO_BOARD) + set(BOARD_TYPE "waveshare-s3-audio-board") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_8) + set(BOARD_TYPE "esp32-s3-touch-amoled-1.8") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_2_06) + set(BOARD_TYPE "waveshare-s3-touch-amoled-2.06") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_2_06) + set(BOARD_TYPE "waveshare-c6-touch-amoled-2.06") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_4B) + set(BOARD_TYPE "waveshare-s3-touch-lcd-4b") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_75) + set(BOARD_TYPE "waveshare-s3-touch-amoled-1.75") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_83) + set(BOARD_TYPE "waveshare-s3-touch-lcd-1.83") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_85C) + set(BOARD_TYPE "esp32-s3-touch-lcd-1.85c") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_85) + set(BOARD_TYPE "esp32-s3-touch-lcd-1.85") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_46) + set(BOARD_TYPE "esp32-s3-touch-lcd-1.46") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_5) + set(BOARD_TYPE "esp32-s3-touch-lcd-3.5") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_5B) + set(BOARD_TYPE "waveshare-s3-touch-lcd-3.5b") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_ePaper_1_54) + set(BOARD_TYPE "waveshare-s3-epaper-1.54") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_49) + set(BOARD_TYPE "waveshare-s3-touch-lcd-3.49") + set(LVGL_TEXT_FONT font_puhui_basic_30_4) + set(LVGL_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_C6_LCD_1_69) + set(BOARD_TYPE "waveshare-c6-lcd-1.69") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_1_43) + set(BOARD_TYPE "waveshare-c6-touch-amoled-1.43") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_1_32) + set(BOARD_TYPE "waveshare-c6-touch-amoled-1.32") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_32) + set(BOARD_TYPE "waveshare-s3-touch-amoled-1.32") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_P4_NANO) + set(BOARD_TYPE "waveshare-p4-nano") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_4B) + set(BOARD_TYPE "waveshare-p4-wifi6-touch-lcd-4b") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_7B) + set(BOARD_TYPE "waveshare-p4-wifi6-touch-lcd-7b") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_XC) + set(BOARD_TYPE "waveshare-p4-wifi6-touch-lcd-xc") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_P4_FUNCTION_EV_BOARD) + set(BOARD_TYPE "esp-p4-function-ev-board") +elseif(CONFIG_BOARD_TYPE_BREAD_COMPACT_WIFI_LCD) + set(BOARD_TYPE "bread-compact-wifi-lcd") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_TUDOUZI) + set(BOARD_TYPE "tudouzi") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_CIRCLE_S3) + set(BOARD_TYPE "lilygo-t-circle-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1) + set(BOARD_TYPE "lilygo-t-cameraplus-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2) + set(BOARD_TYPE "lilygo-t-cameraplus-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_DISPLAY_S3_PRO_MVSRLORA) + set(BOARD_TYPE "lilygo-t-display-s3-pro-mvsrlora") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_DISPLAY_S3_PRO_MVSRLORA_NO_BATTERY) + set(BOARD_TYPE "lilygo-t-display-s3-pro-mvsrlora") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LILYGO_T_DISPLAY_P4) + set(BOARD_TYPE "lilygo-t-display-p4") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_MOVECALL_MOJI_ESP32S3) + set(BOARD_TYPE "movecall-moji-esp32s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_MOVECALL_CUICAN_ESP32S3) + set(BOARD_TYPE "movecall-cuican-esp32s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3) + set(BOARD_TYPE "atk-dnesp32s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3_BOX) + set(BOARD_TYPE "atk-dnesp32s3-box") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3_BOX0) + set(BOARD_TYPE "atk-dnesp32s3-box0") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3_BOX2_WIFI) + set(BOARD_TYPE "atk-dnesp32s3-box2-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3_BOX2_4G) + set(BOARD_TYPE "atk-dnesp32s3-box2-4g") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3M_WIFI) + set(BOARD_TYPE "atk-dnesp32s3m-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_ATK_DNESP32S3M_4G) + set(BOARD_TYPE "atk-dnesp32s3m-4g") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_DU_CHATX) + set(BOARD_TYPE "du-chatx") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_TAIJI_PI_S3) + set(BOARD_TYPE "taiji-pi-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_0_85TFT_WIFI) + set(BOARD_TYPE "xingzhi-cube-0.85tft-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_0_85TFT_ML307) + set(BOARD_TYPE "xingzhi-cube-0.85tft-ml307") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_0_96OLED_WIFI) + set(BOARD_TYPE "xingzhi-cube-0.96oled-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_0_96OLED_ML307) + set(BOARD_TYPE "xingzhi-cube-0.96oled-ml307") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_1_54TFT_WIFI) + set(BOARD_TYPE "xingzhi-cube-1.54tft-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_XINGZHI_CUBE_1_54TFT_ML307) + set(BOARD_TYPE "xingzhi-cube-1.54tft-ml307") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_XINGZHI_METAL_1_54_WIFI) + set(BOARD_TYPE "xingzhi-metal-1.54-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_SEEED_STUDIO_SENSECAP_WATCHER) + set(BOARD_TYPE "sensecap-watcher") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_DOIT_S3_AIBOX) + set(BOARD_TYPE "doit-s3-aibox") +elseif(CONFIG_BOARD_TYPE_MIXGO_NOVA) + set(BOARD_TYPE "mixgo-nova") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_GENJUTECH_S3_1_54TFT) + set(BOARD_TYPE "genjutech-s3-1.54tft") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_CGC) + set(BOARD_TYPE "esp32-cgc") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_CGC_144) + set(BOARD_TYPE "esp32-cgc-144") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +elseif(CONFIG_BOARD_TYPE_ESP_S3_LCD_EV_Board) + set(BOARD_TYPE "esp-s3-lcd-ev-board") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ESP_S3_LCD_EV_Board_2) + set(BOARD_TYPE "esp-s3-lcd-ev-board-2") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ZHENGCHEN_1_54TFT_WIFI) + set(BOARD_TYPE "zhengchen-1.54tft-wifi") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_MINSI_K08_DUAL) + set(BOARD_TYPE "minsi-k08-dual") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_ZHENGCHEN_1_54TFT_ML307) + set(BOARD_TYPE "zhengchen-1.54tft-ml307") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_SPOTPEAR_ESP32_S3_1_54_MUMA) + set(BOARD_TYPE "sp-esp32-s3-1.54-muma") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_SPOTPEAR_ESP32_S3_1_28_BOX) + set(BOARD_TYPE "sp-esp32-s3-1.28-box") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_OTTO_ROBOT) + set(BOARD_TYPE "otto-robot") + set(BUILTIN_TEXT_FONT font_puhui_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) +elseif(CONFIG_BOARD_TYPE_ELECTRON_BOT) + set(BOARD_TYPE "electron-bot") + set(BUILTIN_TEXT_FONT font_puhui_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) +elseif(CONFIG_BOARD_TYPE_BREAD_COMPACT_WIFI_CAM) + set(BOARD_TYPE "bread-compact-wifi-s3cam") + set(BUILTIN_TEXT_FONT font_puhui_basic_16_4) + set(BUILTIN_ICON_FONT font_awesome_16_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_JIUCHUAN) + set(BOARD_TYPE "jiuchuan-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LABPLUS_MPYTHON_V3) + set(BOARD_TYPE "labplus-mpython-v3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_LABPLUS_LEDONG_V2) + set(BOARD_TYPE "labplus-ledong-v2") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_SURFER_C3_1_14TFT) + set(BOARD_TYPE "surfer-c3-1.14tft") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_YUNLIAO_S3) + set(BOARD_TYPE "yunliao-s3") + set(BUILTIN_TEXT_FONT font_puhui_basic_20_4) + set(BUILTIN_ICON_FONT font_awesome_20_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_WIRELESS_TAG_WTP4C5MP07S) + set(BOARD_TYPE "wireless-tag-wtp4c5mp07s") + set(BUILTIN_TEXT_FONT font_puhui_basic_30_4) + set(BUILTIN_ICON_FONT font_awesome_30_4) + set(DEFAULT_EMOJI_COLLECTION twemoji_64) +elseif(CONFIG_BOARD_TYPE_AIPI_LITE) + set(BOARD_TYPE "aipi-lite") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) + set(DEFAULT_EMOJI_COLLECTION twemoji_32) +elseif(CONFIG_BOARD_TYPE_HU_087) + set(BOARD_TYPE "hu-087") + set(BUILTIN_TEXT_FONT font_puhui_basic_14_1) + set(BUILTIN_ICON_FONT font_awesome_14_1) +endif() + +file(GLOB BOARD_SOURCES + ${CMAKE_CURRENT_SOURCE_DIR}/boards/${BOARD_TYPE}/*.cc + ${CMAKE_CURRENT_SOURCE_DIR}/boards/${BOARD_TYPE}/*.c +) +list(APPEND SOURCES ${BOARD_SOURCES}) + +# Select audio processor according to Kconfig +if(CONFIG_USE_AUDIO_PROCESSOR) + list(APPEND SOURCES "audio/processors/afe_audio_processor.cc") +else() + list(APPEND SOURCES "audio/processors/no_audio_processor.cc") +endif() +if(CONFIG_IDF_TARGET_ESP32S3 OR CONFIG_IDF_TARGET_ESP32P4) + list(APPEND SOURCES "audio/wake_words/afe_wake_word.cc") + list(APPEND SOURCES "audio/wake_words/custom_wake_word.cc") +else() + list(APPEND SOURCES "audio/wake_words/esp_wake_word.cc") +endif() + +# Select language directory according to Kconfig +if(CONFIG_LANGUAGE_ZH_CN) + set(LANG_DIR "zh-CN") +elseif(CONFIG_LANGUAGE_ZH_TW) + set(LANG_DIR "zh-TW") +elseif(CONFIG_LANGUAGE_EN_US) + set(LANG_DIR "en-US") +elseif(CONFIG_LANGUAGE_JA_JP) + set(LANG_DIR "ja-JP") +elseif(CONFIG_LANGUAGE_KO_KR) + set(LANG_DIR "ko-KR") +elseif(CONFIG_LANGUAGE_VI_VN) + set(LANG_DIR "vi-VN") +elseif(CONFIG_LANGUAGE_TH_TH) + set(LANG_DIR "th-TH") +elseif(CONFIG_LANGUAGE_DE_DE) + set(LANG_DIR "de-DE") +elseif(CONFIG_LANGUAGE_FR_FR) + set(LANG_DIR "fr-FR") +elseif(CONFIG_LANGUAGE_ES_ES) + set(LANG_DIR "es-ES") +elseif(CONFIG_LANGUAGE_IT_IT) + set(LANG_DIR "it-IT") +elseif(CONFIG_LANGUAGE_RU_RU) + set(LANG_DIR "ru-RU") +elseif(CONFIG_LANGUAGE_AR_SA) + set(LANG_DIR "ar-SA") +elseif(CONFIG_LANGUAGE_HI_IN) + set(LANG_DIR "hi-IN") +elseif(CONFIG_LANGUAGE_PT_PT) + set(LANG_DIR "pt-PT") +elseif(CONFIG_LANGUAGE_PL_PL) + set(LANG_DIR "pl-PL") +elseif(CONFIG_LANGUAGE_CS_CZ) + set(LANG_DIR "cs-CZ") +elseif(CONFIG_LANGUAGE_FI_FI) + set(LANG_DIR "fi-FI") +elseif(CONFIG_LANGUAGE_TR_TR) + set(LANG_DIR "tr-TR") +elseif(CONFIG_LANGUAGE_ID_ID) + set(LANG_DIR "id-ID") +elseif(CONFIG_LANGUAGE_UK_UA) + set(LANG_DIR "uk-UA") +elseif(CONFIG_LANGUAGE_RO_RO) + set(LANG_DIR "ro-RO") +elseif(CONFIG_LANGUAGE_BG_BG) + set(LANG_DIR "bg-BG") +elseif(CONFIG_LANGUAGE_CA_ES) + set(LANG_DIR "ca-ES") +elseif(CONFIG_LANGUAGE_DA_DK) + set(LANG_DIR "da-DK") +elseif(CONFIG_LANGUAGE_EL_GR) + set(LANG_DIR "el-GR") +elseif(CONFIG_LANGUAGE_FA_IR) + set(LANG_DIR "fa-IR") +elseif(CONFIG_LANGUAGE_FIL_PH) + set(LANG_DIR "fil-PH") +elseif(CONFIG_LANGUAGE_HE_IL) + set(LANG_DIR "he-IL") +elseif(CONFIG_LANGUAGE_HR_HR) + set(LANG_DIR "hr-HR") +elseif(CONFIG_LANGUAGE_HU_HU) + set(LANG_DIR "hu-HU") +elseif(CONFIG_LANGUAGE_MS_MY) + set(LANG_DIR "ms-MY") +elseif(CONFIG_LANGUAGE_NB_NO) + set(LANG_DIR "nb-NO") +elseif(CONFIG_LANGUAGE_NL_NL) + set(LANG_DIR "nl-NL") +elseif(CONFIG_LANGUAGE_SK_SK) + set(LANG_DIR "sk-SK") +elseif(CONFIG_LANGUAGE_SL_SI) + set(LANG_DIR "sl-SI") +elseif(CONFIG_LANGUAGE_SV_SE) + set(LANG_DIR "sv-SE") +elseif(CONFIG_LANGUAGE_SR_RS) + set(LANG_DIR "sr-RS") +endif() + +# Define generation path +set(LANG_JSON "${CMAKE_CURRENT_SOURCE_DIR}/assets/locales/${LANG_DIR}/language.json") +set(LANG_HEADER "${CMAKE_CURRENT_SOURCE_DIR}/assets/lang_config.h") + +# Collect current language audio files +file(GLOB LANG_SOUNDS ${CMAKE_CURRENT_SOURCE_DIR}/assets/locales/${LANG_DIR}/*.ogg) + +# If not en-US, collect en-US audio files as fallback for missing files +if(NOT LANG_DIR STREQUAL "en-US") + file(GLOB EN_US_SOUNDS ${CMAKE_CURRENT_SOURCE_DIR}/assets/locales/en-US/*.ogg) + + # Extract filenames (without path) from current language + set(EXISTING_NAMES "") + foreach(SOUND_FILE ${LANG_SOUNDS}) + get_filename_component(FILENAME ${SOUND_FILE} NAME) + list(APPEND EXISTING_NAMES ${FILENAME}) + endforeach() + + # Only add en-US audio files that are missing in current language + foreach(EN_SOUND ${EN_US_SOUNDS}) + get_filename_component(FILENAME ${EN_SOUND} NAME) + if(NOT ${FILENAME} IN_LIST EXISTING_NAMES) + list(APPEND LANG_SOUNDS ${EN_SOUND}) + message(STATUS "Using en-US fallback for missing audio: ${FILENAME}") + endif() + endforeach() +endif() + +file(GLOB COMMON_SOUNDS ${CMAKE_CURRENT_SOURCE_DIR}/assets/common/*.ogg) + +# If target chip is ESP32, exclude specific files to avoid build errors +if(CONFIG_IDF_TARGET_ESP32) + list(REMOVE_ITEM SOURCES "audio/codecs/box_audio_codec.cc" + "audio/codecs/es8388_audio_codec.cc" + "audio/codecs/es8389_audio_codec.cc" + "led/gpio_led.cc" + "${CMAKE_CURRENT_SOURCE_DIR}/boards/common/esp32_camera.cc" + "display/lvgl_display/jpg/image_to_jpeg.cpp" + "display/lvgl_display/jpg/jpeg_to_image.c" + ) +endif() + +idf_component_register(SRCS ${SOURCES} + EMBED_FILES ${LANG_SOUNDS} ${COMMON_SOUNDS} + INCLUDE_DIRS ${INCLUDE_DIRS} + WHOLE_ARCHIVE + ) + +# Use target_compile_definitions to define BOARD_TYPE, BOARD_NAME +# If BOARD_NAME is empty, use BOARD_TYPE +if(NOT BOARD_NAME) + set(BOARD_NAME ${BOARD_TYPE}) +endif() +target_compile_definitions(${COMPONENT_LIB} + PRIVATE BOARD_TYPE=\"${BOARD_TYPE}\" BOARD_NAME=\"${BOARD_NAME}\" + PRIVATE BUILTIN_TEXT_FONT=${BUILTIN_TEXT_FONT} BUILTIN_ICON_FONT=${BUILTIN_ICON_FONT} + ) + +# Add generation rules +add_custom_command( + OUTPUT ${LANG_HEADER} + COMMAND python ${PROJECT_DIR}/scripts/gen_lang.py + --language "${LANG_DIR}" + --output "${LANG_HEADER}" + DEPENDS + ${LANG_JSON} + ${PROJECT_DIR}/scripts/gen_lang.py + COMMENT "Generating ${LANG_DIR} language config" +) + +# Force build generation dependencies +add_custom_target(lang_header ALL + DEPENDS ${LANG_HEADER} +) + +# Find ESP-SR component dynamically +find_component_by_pattern("espressif__esp-sr" ESP_SR_COMPONENT ESP_SR_COMPONENT_PATH) +if(ESP_SR_COMPONENT_PATH) + set(ESP_SR_MODEL_PATH "${ESP_SR_COMPONENT_PATH}/model") +endif() + +# Find xiaozhi-fonts component dynamically +find_component_by_pattern("xiaozhi-fonts" XIAOZHI_FONTS_COMPONENT XIAOZHI_FONTS_COMPONENT_PATH) +if(XIAOZHI_FONTS_COMPONENT_PATH) + set(XIAOZHI_FONTS_PATH "${XIAOZHI_FONTS_COMPONENT_PATH}") +endif() + +if(CONFIG_BOARD_TYPE_ESP_HI) +set(URL "https://github.com/espressif2022/image_player/raw/main/test_apps/test_8bit") +set(EMOJI_DIR "${CMAKE_BINARY_DIR}/emoji") +file(MAKE_DIRECTORY ${EMOJI_DIR}) + +# List all files to download +set(FILES_TO_DOWNLOAD "") +list(APPEND FILES_TO_DOWNLOAD "Anger_enter.aaf" "Anger_loop.aaf" "Anger_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "happy_enter.aaf" "happy_loop.aaf" "happ_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "sad_enter.aaf" "sad_loop.aaf" "sad_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "scorn_enter.aaf" "scorn_loop.aaf" "scorn_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "left_enter.aaf" "left_loop.aaf" "left_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "right_enter.aaf" "right_loop.aaf" "right_return.aaf") +list(APPEND FILES_TO_DOWNLOAD "asking.aaf" "blink_once.aaf" "blink_quick.aaf") +list(APPEND FILES_TO_DOWNLOAD "connecting.aaf" "panic_enter.aaf" "panic_loop.aaf") +list(APPEND FILES_TO_DOWNLOAD "panic_return.aaf" "wake.aaf") + +foreach(FILENAME IN LISTS FILES_TO_DOWNLOAD) + set(REMOTE_FILE "${URL}/${FILENAME}") + set(LOCAL_FILE "${EMOJI_DIR}/${FILENAME}") + + # Check if local file exists + if(EXISTS ${LOCAL_FILE}) + message(STATUS "File ${FILENAME} already exists, skipping download") + else() + message(STATUS "Downloading ${FILENAME}") + file(DOWNLOAD ${REMOTE_FILE} ${LOCAL_FILE} + STATUS DOWNLOAD_STATUS) + list(GET DOWNLOAD_STATUS 0 STATUS_CODE) + if(NOT STATUS_CODE EQUAL 0) + message(FATAL_ERROR "Failed to download ${FILENAME} from ${URL}") + endif() + endif() +endforeach() + +endif() + + +# Function to build default assets based on configuration +function(build_default_assets_bin) + # Set output path for generated assets.bin + set(GENERATED_ASSETS_BIN "${CMAKE_BINARY_DIR}/generated_assets.bin") + + # Prepare arguments for build script + set(BUILD_ARGS + "--sdkconfig" "${SDKCONFIG}" + "--output" "${GENERATED_ASSETS_BIN}" + ) + + # Add builtin text font if defined + if(BUILTIN_TEXT_FONT) + list(APPEND BUILD_ARGS "--builtin_text_font" "${BUILTIN_TEXT_FONT}") + endif() + + # Add default emoji collection if defined + if(DEFAULT_EMOJI_COLLECTION) + list(APPEND BUILD_ARGS "--emoji_collection" "${DEFAULT_EMOJI_COLLECTION}") + endif() + + # Add default assets extra files if defined + if(DEFAULT_ASSETS_EXTRA_FILES) + list(APPEND BUILD_ARGS "--extra_files" "${DEFAULT_ASSETS_EXTRA_FILES}") + endif() + + list(APPEND BUILD_ARGS "--esp_sr_model_path" "${ESP_SR_MODEL_PATH}") + list(APPEND BUILD_ARGS "--xiaozhi_fonts_path" "${XIAOZHI_FONTS_PATH}") + + # Create custom command to build assets + add_custom_command( + OUTPUT ${GENERATED_ASSETS_BIN} + COMMAND python ${PROJECT_DIR}/scripts/build_default_assets.py ${BUILD_ARGS} + DEPENDS + ${SDKCONFIG} + ${PROJECT_DIR}/scripts/build_default_assets.py + COMMENT "Building default assets.bin based on configuration" + VERBATIM + ) + + # Create target for generated assets + add_custom_target(generated_default_assets ALL + DEPENDS ${GENERATED_ASSETS_BIN} + ) + + # Set the generated file path in parent scope + set(GENERATED_ASSETS_LOCAL_FILE ${GENERATED_ASSETS_BIN} PARENT_SCOPE) + + message(STATUS "Default assets build configured: ${GENERATED_ASSETS_BIN}") +endfunction() + + +# Function to get local assets file path (handles both URL and local file) +function(get_assets_local_file assets_source assets_local_file_var) + # Check if it's a URL (starts with http:// or https://) + if(assets_source MATCHES "^https?://") + # It's a URL, download it + get_filename_component(ASSETS_FILENAME "${assets_source}" NAME) + set(ASSETS_LOCAL_FILE "${CMAKE_BINARY_DIR}/${ASSETS_FILENAME}") + set(ASSETS_TEMP_FILE "${CMAKE_BINARY_DIR}/${ASSETS_FILENAME}.tmp") + + # Check if local file exists + if(EXISTS ${ASSETS_LOCAL_FILE}) + message(STATUS "Assets file ${ASSETS_FILENAME} already exists, skipping download") + else() + message(STATUS "Downloading ${ASSETS_FILENAME}") + + # Clean up any existing temp file + if(EXISTS ${ASSETS_TEMP_FILE}) + file(REMOVE ${ASSETS_TEMP_FILE}) + endif() + + # Download to temporary file first + file(DOWNLOAD ${assets_source} ${ASSETS_TEMP_FILE} + STATUS DOWNLOAD_STATUS) + list(GET DOWNLOAD_STATUS 0 STATUS_CODE) + if(NOT STATUS_CODE EQUAL 0) + # Clean up temp file on failure + if(EXISTS ${ASSETS_TEMP_FILE}) + file(REMOVE ${ASSETS_TEMP_FILE}) + endif() + message(FATAL_ERROR "Failed to download ${ASSETS_FILENAME} from ${assets_source}") + endif() + + # Move temp file to final location (atomic operation) + file(RENAME ${ASSETS_TEMP_FILE} ${ASSETS_LOCAL_FILE}) + message(STATUS "Successfully downloaded ${ASSETS_FILENAME}") + endif() + else() + # It's a local file path + if(IS_ABSOLUTE "${assets_source}") + set(ASSETS_LOCAL_FILE "${assets_source}") + else() + set(ASSETS_LOCAL_FILE "${CMAKE_CURRENT_SOURCE_DIR}/${assets_source}") + endif() + + # Check if local file exists + if(NOT EXISTS ${ASSETS_LOCAL_FILE}) + message(FATAL_ERROR "Assets file not found: ${ASSETS_LOCAL_FILE}") + endif() + + message(STATUS "Using assets file: ${ASSETS_LOCAL_FILE}") + endif() + + set(${assets_local_file_var} ${ASSETS_LOCAL_FILE} PARENT_SCOPE) +endfunction() + + +partition_table_get_partition_info(size "--partition-name assets" "size") +partition_table_get_partition_info(offset "--partition-name assets" "offset") +if ("${size}" AND "${offset}") + # Flash assets based on configuration + if(CONFIG_FLASH_DEFAULT_ASSETS) + # Build default assets based on configuration + build_default_assets_bin() + esptool_py_flash_to_partition(flash "assets" "${GENERATED_ASSETS_LOCAL_FILE}") + message(STATUS "Generated default assets flash configured: ${GENERATED_ASSETS_LOCAL_FILE} -> assets partition") + elseif(CONFIG_FLASH_CUSTOM_ASSETS) + # Flash custom assets + get_assets_local_file("${CONFIG_CUSTOM_ASSETS_FILE}" ASSETS_LOCAL_FILE) + esptool_py_flash_to_partition(flash "assets" "${ASSETS_LOCAL_FILE}") + message(STATUS "Custom assets flash configured: ${ASSETS_LOCAL_FILE} -> assets partition") + elseif(CONFIG_FLASH_NONE_ASSETS) + message(STATUS "Assets flashing disabled (FLASH_NONE_ASSETS)") + endif() +else() + message(STATUS "Assets partition not found, using v1 partition table") +endif() diff --git a/main/Kconfig.projbuild b/main/Kconfig.projbuild new file mode 100644 index 0000000..8c18ba5 --- /dev/null +++ b/main/Kconfig.projbuild @@ -0,0 +1,791 @@ +menu "Xiaozhi Assistant" + +config OTA_URL + string "Default OTA URL" + default "https://api.tenclass.net/xiaozhi/ota/" + help + The application will access this URL to check for new firmwares and server address. + +choice + prompt "Flash Assets" + default FLASH_DEFAULT_ASSETS + help + Select the assets to flash. + + config FLASH_NONE_ASSETS + bool "Do not flash assets" + config FLASH_DEFAULT_ASSETS + bool "Flash Default Assets" + config FLASH_CUSTOM_ASSETS + bool "Flash Custom Assets" +endchoice + +config CUSTOM_ASSETS_FILE + depends on FLASH_CUSTOM_ASSETS + string "Custom Assets File" + default "assets.bin" + help + The custom assets file to flash. + It can be a local file relative to the project directory or a remote url. + +choice + prompt "Default Language" + default LANGUAGE_ZH_CN + help + Select device display language + + config LANGUAGE_ZH_CN + bool "Chinese" + config LANGUAGE_ZH_TW + bool "Chinese Traditional" + config LANGUAGE_EN_US + bool "English" + config LANGUAGE_JA_JP + bool "Japanese" + config LANGUAGE_KO_KR + bool "Korean" + config LANGUAGE_VI_VN + bool "Vietnamese" + config LANGUAGE_TH_TH + bool "Thai" + config LANGUAGE_DE_DE + bool "German" + config LANGUAGE_FR_FR + bool "French" + config LANGUAGE_ES_ES + bool "Spanish" + config LANGUAGE_IT_IT + bool "Italian" + config LANGUAGE_RU_RU + bool "Russian" + config LANGUAGE_AR_SA + bool "Arabic" + config LANGUAGE_HI_IN + bool "Hindi" + config LANGUAGE_PT_PT + bool "Portuguese" + config LANGUAGE_PL_PL + bool "Polish" + config LANGUAGE_CS_CZ + bool "Czech" + config LANGUAGE_FI_FI + bool "Finnish" + config LANGUAGE_TR_TR + bool "Turkish" + config LANGUAGE_ID_ID + bool "Indonesian" + config LANGUAGE_UK_UA + bool "Ukrainian" + config LANGUAGE_RO_RO + bool "Romanian" + config LANGUAGE_BG_BG + bool "Bulgarian" + config LANGUAGE_CA_ES + bool "Catalan" + config LANGUAGE_DA_DK + bool "Danish" + config LANGUAGE_EL_GR + bool "Greek" + config LANGUAGE_FA_IR + bool "Persian" + config LANGUAGE_FIL_PH + bool "Filipino" + config LANGUAGE_HE_IL + bool "Hebrew" + config LANGUAGE_HR_HR + bool "Croatian" + config LANGUAGE_HU_HU + bool "Hungarian" + config LANGUAGE_MS_MY + bool "Malay" + config LANGUAGE_NB_NO + bool "Norwegian" + config LANGUAGE_NL_NL + bool "Dutch" + config LANGUAGE_SK_SK + bool "Slovak" + config LANGUAGE_SL_SI + bool "Slovenian" + config LANGUAGE_SV_SE + bool "Swedish" + config LANGUAGE_SR_RS + bool "Serbian" +endchoice + +choice BOARD_TYPE + prompt "Board Type" + default BOARD_TYPE_BREAD_COMPACT_WIFI + help + Board type. 开发板类型 + config BOARD_TYPE_BREAD_COMPACT_WIFI + bool "Bread Compact WiFi (面包板)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_BREAD_COMPACT_WIFI_LCD + bool "Bread Compact WiFi + LCD (面包板)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_BREAD_COMPACT_WIFI_CAM + bool "Bread Compact WiFi + LCD + Camera (面包板)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_BREAD_COMPACT_ML307 + bool "Bread Compact ML307/EC801E (面包板 4G)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_BREAD_COMPACT_ESP32 + bool "Bread Compact ESP32 DevKit (面包板)" + depends on IDF_TARGET_ESP32 + config BOARD_TYPE_BREAD_COMPACT_ESP32_LCD + bool "Bread Compact ESP32 DevKit + LCD (面包板)" + depends on IDF_TARGET_ESP32 + config BOARD_TYPE_XMINI_C3_V3 + bool "Xmini C3 V3" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_XMINI_C3_4G + bool "Xmini C3 4G" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_XMINI_C3 + bool "Xmini C3" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_ESP_KORVO2_V3 + bool "Espressif Korvo2 V3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_SPARKBOT + bool "Espressif SparkBot" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_SPOT_S3 + bool "Espressif Spot-S3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_SPOT_C5 + bool "Espressif Spot-C5" + depends on IDF_TARGET_ESP32C5 + config BOARD_TYPE_ESP_HI + bool "Espressif ESP-HI" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_ESP_BOX_3 + bool "Espressif ESP-BOX-3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_BOX + bool "Espressif ESP-BOX" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_BOX_LITE + bool "Espressif ESP-BOX-Lite" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_P4_FUNCTION_EV_BOARD + bool "Espressif ESP-P4-Function-EV-Board" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_ECHOEAR + bool "EchoEar" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_KEVIN_BOX_2 + bool "Kevin Box 2" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_KEVIN_C3 + bool "Kevin C3" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_KEVIN_SP_V3_DEV + bool "Kevin SP V3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_KEVIN_SP_V4_DEV + bool "Kevin SP V4" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_KEVIN_YUYING_313LCD + bool "鱼鹰科技 3.13LCD" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_CGC + bool "CGC" + depends on IDF_TARGET_ESP32 + config BOARD_TYPE_CGC_144 + bool "CGC 144" + depends on IDF_TARGET_ESP32 + config BOARD_TYPE_LICHUANG_DEV_S3 + bool "立创·实战派 ESP32-S3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LICHUANG_DEV_C3 + bool "立创·实战派 ESP32-C3" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_DF_K10 + bool "DFRobot 行空板 k10" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_DF_S3_AI_CAM + bool "DFRobot ESP32-S3 AI智能摄像头模块" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MAGICLICK_S3_2P4 + bool "神奇按钮 Magiclick_2.4" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MAGICLICK_S3_2P5 + bool "神奇按钮 Magiclick_2.5" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MAGICLICK_C3 + bool "神奇按钮 Magiclick_C3" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_MAGICLICK_C3_V2 + bool "神奇按钮 Magiclick_C3_v2" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_M5STACK_CORE_S3 + bool "M5Stack CoreS3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_M5STACK_CORE_TAB5 + bool "M5Stack Tab5" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_M5STACK_ATOM_S3_ECHO_BASE + bool "M5Stack AtomS3 + Echo Base" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_M5STACK_ATOM_S3R_ECHO_BASE + bool "M5Stack AtomS3R + Echo Base" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_M5STACK_ATOM_S3R_CAM_M12_ECHO_BASE + bool "M5Stack AtomS3R CAM/M12 + Echo Base" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_M5STACK_ATOM_ECHOS3R + bool "M5Stack AtomEchoS3R" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_M5STACK_ATOM_MATRIX_ECHO_BASE + bool "M5Stack AtomMatrix + Echo Base" + depends on IDF_TARGET_ESP32 + config BOARD_TYPE_WAVESHARE_S3_AUDIO_BOARD + bool "Waveshare ESP32-S3-Audio-Board" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_8 + bool "Waveshare ESP32-S3-Touch-AMOLED-1.8" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_2_06 + bool "Waveshare ESP32-S3-Touch-AMOLED-2.06" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_2_06 + bool "Waveshare ESP32-C6-Touch-AMOLED-2.06" + depends on IDF_TARGET_ESP32C6 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_75 + bool "Waveshare ESP32-S3-Touch-AMOLED-1.75" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_83 + bool "Waveshare ESP32-S3-Touch-LCD-1.83" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_4B + bool "Waveshare ESP32-S3-Touch-LCD-4B" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_85C + bool "Waveshare ESP32-S3-Touch-LCD-1.85C" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_85 + bool "Waveshare ESP32-S3-Touch-LCD-1.85" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_46 + bool "Waveshare ESP32-S3-Touch-LCD-1.46" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_C6_LCD_1_69 + bool "Waveshare ESP32-C6-LCD-1.69" + depends on IDF_TARGET_ESP32C6 + config BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_1_43 + bool "Waveshare ESP32-C6-Touch-AMOLOED-1.43" + depends on IDF_TARGET_ESP32C6 + config BOARD_TYPE_WAVESHARE_C6_TOUCH_AMOLED_1_32 + bool "Waveshare ESP32-C6-Touch-AMOLOED-1.32" + depends on IDF_TARGET_ESP32C6 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_32 + bool "Waveshare ESP32-S3-Touch-AMOLOED-1.32" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_49 + bool "Waveshare ESP32-S3-Touch-LCD-3.49" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_5 + bool "Waveshare ESP32-S3-Touch-LCD-3.5" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_ePaper_1_54 + bool "Waveshare ESP32-S3-ePaper-1.54" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_5B + bool "Waveshare ESP32-S3-Touch-LCD-3.5B" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WAVESHARE_P4_NANO + bool "Waveshare ESP32-P4-NANO" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_4B + bool "Waveshare ESP32-P4-WIFI6-Touch-LCD-4B" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_7B + bool "Waveshare ESP32-P4-WIFI6-Touch-LCD-7B" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_XC + bool "Waveshare ESP32-P4-WIFI6-Touch-LCD-3.4C or ESP32-P4-WIFI6-Touch-LCD-4C" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_TUDOUZI + bool "土豆子" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_CIRCLE_S3 + bool "LILYGO T-Circle-S3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1 + bool "LILYGO T-CameraPlus-S3_V1_0_V1_1" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 + bool "LILYGO T-CameraPlus-S3_V1_2" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_DISPLAY_S3_PRO_MVSRLORA + bool "LILYGO T-Display-S3-Pro-MVSRLora" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_DISPLAY_S3_PRO_MVSRLORA_NO_BATTERY + bool "LILYGO T-Display-S3-Pro-MVSRLora_No_Battery" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LILYGO_T_DISPLAY_P4 + bool "LILYGO T-Display-P4" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_MOVECALL_MOJI_ESP32S3 + bool "Movecall Moji 小智AI衍生版" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MOVECALL_CUICAN_ESP32S3 + bool "Movecall CuiCan 璀璨·AI吊坠" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3 + bool "正点原子DNESP32S3开发板" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3_BOX + bool "正点原子DNESP32S3-BOX" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3_BOX0 + bool "正点原子DNESP32S3-BOX0" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3_BOX2_WIFI + bool "正点原子DNESP32S3-BOX2-WIFI" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3_BOX2_4G + bool "正点原子DNESP32S3-BOX2-4G" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3M_WIFI + bool "正点原子DNESP32S3M-WIFI" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ATK_DNESP32S3M_4G + bool "正点原子DNESP32S3M-4G" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_DU_CHATX + bool "嘟嘟开发板CHATX(wifi)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_TAIJI_PI_S3 + bool "太极小派esp32s3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_0_85TFT_WIFI + bool "无名科技星智0.85(WIFI)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_0_85TFT_ML307 + bool "无名科技星智0.85(ML307)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_0_96OLED_WIFI + bool "无名科技星智0.96(WIFI)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_0_96OLED_ML307 + bool "无名科技星智0.96(ML307)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_1_54TFT_WIFI + bool "无名科技星智1.54(WIFI)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_CUBE_1_54TFT_ML307 + bool "无名科技星智1.54(ML307)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_XINGZHI_METAL_1_54_WIFI + bool "无名科技星智1.54 METAL(wifi)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_SEEED_STUDIO_SENSECAP_WATCHER + bool "Seeed Studio SenseCAP Watcher" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_DOIT_S3_AIBOX + bool "四博智联AI陪伴盒子" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MIXGO_NOVA + bool "元控·青春" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_GENJUTECH_S3_1_54TFT + bool "亘具科技1.54(s3)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_S3_LCD_EV_Board + bool "乐鑫ESP S3 LCD EV Board开发板" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ESP_S3_LCD_EV_Board_2 + bool "乐鑫ESP S3 LCD EV Board 2开发板" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ZHENGCHEN_1_54TFT_WIFI + bool "征辰科技1.54(WIFI)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ZHENGCHEN_1_54TFT_ML307 + bool "征辰科技1.54(ML307)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_MINSI_K08_DUAL + bool "敏思科技K08(DUAL)" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_SPOTPEAR_ESP32_S3_1_54_MUMA + bool "Spotpear ESP32-S3-1.54-MUMA" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_SPOTPEAR_ESP32_S3_1_28_BOX + bool "Spotpear ESP32-S3-1.28-BOX" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_OTTO_ROBOT + bool "ottoRobot" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_ELECTRON_BOT + bool "electronBot" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_JIUCHUAN + bool "九川智能" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LABPLUS_MPYTHON_V3 + bool "labplus mpython_v3 board" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_LABPLUS_LEDONG_V2 + bool "labplus ledong_v2 board" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_SURFER_C3_1_14TFT + bool "Surfer-C3-1.14TFT" + depends on IDF_TARGET_ESP32C3 + config BOARD_TYPE_YUNLIAO_S3 + bool "小智云聊-S3" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_WIRELESS_TAG_WTP4C5MP07S + bool "Wireless-Tag WTP4C5MP07S" + depends on IDF_TARGET_ESP32P4 + config BOARD_TYPE_AIPI_LITE + bool "AIPI-Lite" + depends on IDF_TARGET_ESP32S3 + config BOARD_TYPE_HU_087 + bool "HU-087" + depends on IDF_TARGET_ESP32S3 +endchoice + +choice + depends on BOARD_TYPE_LILYGO_T_DISPLAY_P4 + prompt "Select the screen type" + default SCREEN_TYPE_HI8561 + config SCREEN_TYPE_HI8561 + bool "HI8561" + config SCREEN_TYPE_RM69A10 + bool "RM69A10" +endchoice + +choice + depends on BOARD_TYPE_LILYGO_T_DISPLAY_P4 + prompt "Select the color format of the screen" + default SCREEN_PIXEL_FORMAT_RGB565 + config SCREEN_PIXEL_FORMAT_RGB565 + bool "RGB565" + config SCREEN_PIXEL_FORMAT_RGB888 + bool "RGB888" +endchoice + +choice ESP_S3_LCD_EV_Board_Version_TYPE + depends on BOARD_TYPE_ESP_S3_LCD_EV_Board + prompt "EV_BOARD Type" + default ESP_S3_LCD_EV_Board_1p4 + config ESP_S3_LCD_EV_Board_1p4 + bool "乐鑫ESP32_S3_LCD_EV_Board-MB_V1.4" + config ESP_S3_LCD_EV_Board_1p5 + bool "乐鑫ESP32_S3_LCD_EV_Board-MB_V1.5" +endchoice + +choice DISPLAY_OLED_TYPE + depends on BOARD_TYPE_BREAD_COMPACT_WIFI || BOARD_TYPE_BREAD_COMPACT_ML307 || BOARD_TYPE_BREAD_COMPACT_ESP32 || BOARD_TYPE_HU_087 + prompt "OLED Type" + default OLED_SSD1306_128X32 + help + OLED Monochrome Display Type + config OLED_SSD1306_128X32 + bool "SSD1306 128*32" + config OLED_SSD1306_128X64 + bool "SSD1306 128*64" + config OLED_SH1106_128X64 + bool "SH1106 128*64" +endchoice + +choice DISPLAY_LCD_TYPE + depends on BOARD_TYPE_BREAD_COMPACT_WIFI_LCD || BOARD_TYPE_BREAD_COMPACT_ESP32_LCD || BOARD_TYPE_CGC || BOARD_TYPE_WAVESHARE_P4_NANO || BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_XC || BOARD_TYPE_BREAD_COMPACT_WIFI_CAM + prompt "LCD Type" + default LCD_ST7789_240X320 + help + LCD Display Type + config LCD_ST7789_240X320 + bool "ST7789 240*320, IPS" + config LCD_ST7789_240X320_NO_IPS + bool "ST7789 240*320, Non-IPS" + config LCD_ST7789_170X320 + bool "ST7789 170*320" + config LCD_ST7789_172X320 + bool "ST7789 172*320" + config LCD_ST7789_240X280 + bool "ST7789 240*280" + config LCD_ST7789_240X240 + bool "ST7789 240*240" + config LCD_ST7789_240X240_7PIN + bool "ST7789 240*240, 7PIN" + config LCD_ST7789_240X135 + bool "ST7789 240*135" + config LCD_ST7735_128X160 + bool "ST7735 128*160" + config LCD_ST7735_128X128 + bool "ST7735 128*128" + config LCD_ST7796_320X480 + bool "ST7796 320*480 IPS" + config LCD_ST7796_320X480_NO_IPS + bool "ST7796 320*480, Non-IPS" + config LCD_ILI9341_240X320 + bool "ILI9341 240*320" + config LCD_ILI9341_240X320_NO_IPS + bool "ILI9341 240*320, Non-IPS" + config LCD_GC9A01_240X240 + bool "GC9A01 240*240 Circle" + config LCD_TYPE_800_1280_10_1_INCH + bool "Waveshare 101M-8001280-IPS-CT-K Display" + config LCD_TYPE_800_1280_10_1_INCH_A + bool "Waveshare 10.1-DSI-TOUCH-A Display" + config LCD_TYPE_800_800_3_4_INCH + bool "Waveshare ESP32-P4-WIFI6-Touch-LCD-3.4C with 800*800 3.4inch round display" + config LCD_TYPE_720_720_4_INCH + bool "Waveshare ESP32-P4-WIFI6-Touch-LCD-4C with 720*720 4inch round display" + config LCD_CUSTOM + bool "Custom LCD (自定义屏幕参数)" +endchoice + +choice DISPLAY_ESP32S3_KORVO2_V3 + depends on BOARD_TYPE_ESP_KORVO2_V3 + prompt "ESP32S3_KORVO2_V3 LCD Type" + default ESP32S3_KORVO2_V3_LCD_ST7789 + help + LCD Display Type + config ESP32S3_KORVO2_V3_LCD_ST7789 + bool "ST7789 240*280" + config ESP32S3_KORVO2_V3_LCD_ILI9341 + bool "ILI9341 240*320" +endchoice + +choice DISPLAY_ESP32S3_AUDIO_BOARD + depends on BOARD_TYPE_WAVESHARE_S3_AUDIO_BOARD + prompt "ESP32S3_AUDIO_BOARD LCD Type" + default AUDIO_BOARD_LCD_JD9853 + help + LCD Display Type + config AUDIO_BOARD_LCD_JD9853 + bool "JD9853 320*172" + config AUDIO_BOARD_LCD_ST7789 + bool "ST7789 240*320" +endchoice + +choice DISPLAY_STYLE + prompt "Select display style" + default USE_DEFAULT_MESSAGE_STYLE + help + Select display style for Xiaozhi device + + config USE_DEFAULT_MESSAGE_STYLE + bool "Enable default message style" + + config USE_WECHAT_MESSAGE_STYLE + bool "Enable WeChat Message Style" + + config USE_EMOTE_MESSAGE_STYLE + bool "Emote animation style" + depends on BOARD_TYPE_ESP_BOX_3 || BOARD_TYPE_ECHOEAR || BOARD_TYPE_LICHUANG_DEV_S3 +endchoice + +choice WAKE_WORD_TYPE + prompt "Wake Word Implementation Type" + default USE_AFE_WAKE_WORD if (IDF_TARGET_ESP32S3 || IDF_TARGET_ESP32P4) && SPIRAM + default WAKE_WORD_DISABLED + help + Choose the type of wake word implementation to use + + config WAKE_WORD_DISABLED + bool "Disabled" + help + Disable wake word detection + + config USE_ESP_WAKE_WORD + bool "Wakenet model without AFE" + depends on IDF_TARGET_ESP32C3 || IDF_TARGET_ESP32C5 || IDF_TARGET_ESP32C6 || (IDF_TARGET_ESP32 && SPIRAM) + help + Support ESP32 C3、ESP32 C5 与 ESP32 C6, and (ESP32 with PSRAM) + + config USE_AFE_WAKE_WORD + bool "Wakenet model with AFE" + depends on (IDF_TARGET_ESP32S3 || IDF_TARGET_ESP32P4) && SPIRAM + help + Support AEC if available, requires ESP32 S3 and PSRAM + + config USE_CUSTOM_WAKE_WORD + bool "Multinet model (Custom Wake Word)" + depends on (IDF_TARGET_ESP32S3 || IDF_TARGET_ESP32P4) && SPIRAM + help + Requires ESP32 S3 and PSRAM + +endchoice + +config CUSTOM_WAKE_WORD + string "Custom Wake Word" + default "xiao tu dou" + depends on USE_CUSTOM_WAKE_WORD + help + Custom Wake Word, use pinyin for Chinese, separated by spaces + +config CUSTOM_WAKE_WORD_DISPLAY + string "Custom Wake Word Display" + default "小土豆" + depends on USE_CUSTOM_WAKE_WORD + help + Greeting sent to the server after wake word detection + +config CUSTOM_WAKE_WORD_THRESHOLD + int "Custom Wake Word Threshold (%)" + default 20 + range 1 99 + depends on USE_CUSTOM_WAKE_WORD + help + Custom Wake Word Threshold, range 1-99, the smaller the more sensitive, default 20 + +config SEND_WAKE_WORD_DATA + bool "Send Wake Word Data" + default y + depends on USE_AFE_WAKE_WORD || USE_CUSTOM_WAKE_WORD + help + Send wake word data to the server as the first message of the conversation and wait for response + +config USE_AUDIO_PROCESSOR + bool "Enable Audio Noise Reduction" + default y + depends on (IDF_TARGET_ESP32S3 || IDF_TARGET_ESP32P4) && SPIRAM + help + Requires ESP32 S3 and PSRAM + +config USE_DEVICE_AEC + bool "Enable Device-Side AEC" + default n + depends on USE_AUDIO_PROCESSOR && (BOARD_TYPE_ESP_BOX_3 || BOARD_TYPE_ESP_BOX || BOARD_TYPE_ESP_BOX_LITE \ + || BOARD_TYPE_LICHUANG_DEV_S3 || BOARD_TYPE_ESP_KORVO2_V3 || BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_1_75 || BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_1_83\ + || BOARD_TYPE_WAVESHARE_S3_TOUCH_AMOLED_2_06 || BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_4B || BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_4B || BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_7B \ + || BOARD_TYPE_WAVESHARE_P4_WIFI6_TOUCH_LCD_XC || BOARD_TYPE_ESP_S3_LCD_EV_Board_2 || BOARD_TYPE_YUNLIAO_S3 \ + || BOARD_TYPE_ECHOEAR || BOARD_TYPE_WAVESHARE_S3_TOUCH_LCD_3_49) + help + To work properly, device-side AEC requires a clean output reference path from the speaker signal and physical acoustic isolation between the microphone and speaker. + +config USE_SERVER_AEC + bool "Enable Server-Side AEC (Unstable)" + default n + depends on USE_AUDIO_PROCESSOR + help + To work perperly, server-side AEC requires server support + +config USE_AUDIO_DEBUGGER + bool "Enable Audio Debugger" + default n + help + Enable audio debugger, send audio data through UDP to the host machine + +config AUDIO_DEBUG_UDP_SERVER + string "Audio Debug UDP Server Address" + default "192.168.2.100:8000" + depends on USE_AUDIO_DEBUGGER + help + UDP server address, format: IP:PORT, used to receive audio debugging data + +config USE_ACOUSTIC_WIFI_PROVISIONING + bool "Enable Acoustic WiFi Provisioning" + default n + help + Enable acoustic WiFi provisioning, use audio signal to transmit WiFi configuration data + +config RECEIVE_CUSTOM_MESSAGE + bool "Enable Custom Message Reception" + default n + help + Enable custom message reception, allow the device to receive custom messages from the server (preferably through the MQTT protocol) + +menu "Camera Configuration" + depends on !IDF_TARGET_ESP32 + + comment "Warning: Please read the help text before modifying these settings." + + config XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + bool "Allow JPEG Input" + default n + help + Allow JPEG Input format for the camera. + + This option may need to be enabled when using a USB camera. + + Not currently supported when used simultaneously with XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE. + + config XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + bool "Enable Hardware JPEG Encoder" + default y + depends on SOC_JPEG_ENCODE_SUPPORTED + help + Use hardware JPEG encoder on ESP32-P4 to encode image to JPEG. + See https://docs.espressif.com/projects/esp-idf/en/stable/esp32p4/api-reference/peripherals/jpeg.html for more details. + + config XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER + bool "Enable Hardware JPEG Decoder" + default n + depends on SOC_JPEG_DECODE_SUPPORTED && XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + help + Use hardware JPEG decoder on ESP32-P4 to decode JPEG to image. + See https://docs.espressif.com/projects/esp-idf/en/stable/esp32p4/api-reference/peripherals/jpeg.html for more details. + + config XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + bool "Enable Camera Debug Mode" + default n + help + Enable camera debug mode, print camera debug information to the console. + Only works on boards that support camera. + + config XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP + bool "Enable software camera buffer endianness swapping" + default n + depends on !CAMERA_SENSOR_SWAP_PIXEL_BYTE_ORDER + help + This option treats the camera buffer as a uint16_t[] array and performs byte-swapping (endianness conversion) on each element. + + Should only be modified by development board integration engineers. + + **Incorrect usage may result in incorrect image colors!** + + ATTENTION: If the option CAMERA_SENSOR_SWAP_PIXEL_BYTE_ORDER is available for your sensor, please use that instead. + + menuconfig XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + bool "Enable Camera Image Rotation" + default n + depends on !XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + help + Enable camera image rotation, rotate the camera image to the correct orientation. + - On ESP32-P4, rotation is handled by PPA hardware. + - On other chips, rotation is done in software with performance cost. + - For 180° rotation, use HFlip + VFlip instead of this option. + + Not currently supported when used simultaneously with XIAOZHI_CAMERA_ALLOW_JPEG_INPUT. + + if XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + choice XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE + prompt "Camera Image Rotation Angle (clockwise)" + default XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_90 + help + Camera image rotation angle. + config XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_90 + bool "90°" + config XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_270 + bool "270°" + comment "For 180° rotation, use HFlip + VFlip instead of this option" + endchoice + endif +endmenu + +menu "TAIJIPAI_S3_CONFIG" + depends on BOARD_TYPE_TAIJI_PI_S3 + choice I2S_TYPE_TAIJIPI_S3 + prompt "taiji-pi-S3 I2S Type" + default TAIJIPAI_I2S_TYPE_STD + help + I2S 类型选择 + config TAIJIPAI_I2S_TYPE_STD + bool "I2S Type STD" + config TAIJIPAI_I2S_TYPE_PDM + bool "I2S Type PDM" + endchoice + + config I2S_USE_2SLOT + bool "Enable I2S 2 Slot" + default y + help + 启动双声道 +endmenu + +endmenu diff --git a/main/application.cc b/main/application.cc new file mode 100644 index 0000000..ade4bfc --- /dev/null +++ b/main/application.cc @@ -0,0 +1,910 @@ +#include "application.h" +#include "board.h" +#include "display.h" +#include "system_info.h" +#include "audio_codec.h" +#include "mqtt_protocol.h" +#include "websocket_protocol.h" +#include "assets/lang_config.h" +#include "mcp_server.h" +#include "assets.h" +#include "settings.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "Application" + + +// ESP32 设备状态字符串,用于日志输出 +// 其中 "idle"、"listening"、"speaking" 会通过 UART 发送给 RP2040 驱动舵机动画 +static const char* const STATE_STRINGS[] = { + "unknown", + "starting", + "configuring", + "idle", // → RP2040 执行 state_sleep(闭眼、耳朵收起) + "connecting", + "listening", // → RP2040 执行 state_listen(好奇姿态、眼球随机看) + "speaking", // → RP2040 执行 state_speaking(嘴巴开合、眼球随机看、身体摆动) + "upgrading", + "activating", + "audio_testing", + "fatal_error", + "invalid_state" +}; + +Application::Application() { + event_group_ = xEventGroupCreate(); + +#if CONFIG_USE_DEVICE_AEC && CONFIG_USE_SERVER_AEC +#error "CONFIG_USE_DEVICE_AEC and CONFIG_USE_SERVER_AEC cannot be enabled at the same time" +#elif CONFIG_USE_DEVICE_AEC + aec_mode_ = kAecOnDeviceSide; +#elif CONFIG_USE_SERVER_AEC + aec_mode_ = kAecOnServerSide; +#else + aec_mode_ = kAecOff; +#endif + + esp_timer_create_args_t clock_timer_args = { + .callback = [](void* arg) { + Application* app = (Application*)arg; + xEventGroupSetBits(app->event_group_, MAIN_EVENT_CLOCK_TICK); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "clock_timer", + .skip_unhandled_events = true + }; + esp_timer_create(&clock_timer_args, &clock_timer_handle_); +} + +Application::~Application() { + if (clock_timer_handle_ != nullptr) { + esp_timer_stop(clock_timer_handle_); + esp_timer_delete(clock_timer_handle_); + } + vEventGroupDelete(event_group_); +} + +void Application::CheckAssetsVersion() { + auto& board = Board::GetInstance(); + auto display = board.GetDisplay(); + auto& assets = Assets::GetInstance(); + + if (!assets.partition_valid()) { + ESP_LOGW(TAG, "Assets partition is disabled for board %s", BOARD_NAME); + return; + } + + Settings settings("assets", true); + // Check if there is a new assets need to be downloaded + std::string download_url = settings.GetString("download_url"); + + if (!download_url.empty()) { + settings.EraseKey("download_url"); + + char message[256]; + snprintf(message, sizeof(message), Lang::Strings::FOUND_NEW_ASSETS, download_url.c_str()); + Alert(Lang::Strings::LOADING_ASSETS, message, "cloud_arrow_down", Lang::Sounds::OGG_UPGRADE); + + // Wait for the audio service to be idle for 3 seconds + vTaskDelay(pdMS_TO_TICKS(3000)); + SetDeviceState(kDeviceStateUpgrading); + board.SetPowerSaveMode(false); + display->SetChatMessage("system", Lang::Strings::PLEASE_WAIT); + + bool success = assets.Download(download_url, [display](int progress, size_t speed) -> void { + std::thread([display, progress, speed]() { + char buffer[32]; + snprintf(buffer, sizeof(buffer), "%d%% %uKB/s", progress, speed / 1024); + display->SetChatMessage("system", buffer); + }).detach(); + }); + + board.SetPowerSaveMode(true); + vTaskDelay(pdMS_TO_TICKS(1000)); + + if (!success) { + Alert(Lang::Strings::ERROR, Lang::Strings::DOWNLOAD_ASSETS_FAILED, "circle_xmark", Lang::Sounds::OGG_EXCLAMATION); + vTaskDelay(pdMS_TO_TICKS(2000)); + return; + } + } + + // Apply assets + assets.Apply(); + display->SetChatMessage("system", ""); + display->SetEmotion("microchip_ai"); + uart_send_string("configuring"); +} + +void Application::CheckNewVersion(Ota& ota) { + const int MAX_RETRY = 10; + int retry_count = 0; + int retry_delay = 10; // 初始重试延迟为10秒 + + auto& board = Board::GetInstance(); + while (true) { + SetDeviceState(kDeviceStateActivating); + auto display = board.GetDisplay(); + display->SetStatus(Lang::Strings::CHECKING_NEW_VERSION); + + esp_err_t err = ota.CheckVersion(); + if (err != ESP_OK) { + retry_count++; + if (retry_count >= MAX_RETRY) { + ESP_LOGE(TAG, "Too many retries, exit version check"); + return; + } + + char error_message[128]; + snprintf(error_message, sizeof(error_message), "code=%d, url=%s", err, ota.GetCheckVersionUrl().c_str()); + char buffer[256]; + snprintf(buffer, sizeof(buffer), Lang::Strings::CHECK_NEW_VERSION_FAILED, retry_delay, error_message); + Alert(Lang::Strings::ERROR, buffer, "cloud_slash", Lang::Sounds::OGG_EXCLAMATION); + + ESP_LOGW(TAG, "Check new version failed, retry in %d seconds (%d/%d)", retry_delay, retry_count, MAX_RETRY); + for (int i = 0; i < retry_delay; i++) { + vTaskDelay(pdMS_TO_TICKS(1000)); + if (device_state_ == kDeviceStateIdle) { + break; + } + } + retry_delay *= 2; // 每次重试后延迟时间翻倍 + continue; + } + retry_count = 0; + retry_delay = 10; // 重置重试延迟时间 + + if (ota.HasNewVersion()) { + if (UpgradeFirmware(ota)) { + return; // This line will never be reached after reboot + } + // If upgrade failed, continue to normal operation (don't break, just fall through) + } + + // No new version, mark the current version as valid + ota.MarkCurrentVersionValid(); + if (!ota.HasActivationCode() && !ota.HasActivationChallenge()) { + xEventGroupSetBits(event_group_, MAIN_EVENT_CHECK_NEW_VERSION_DONE); + // Exit the loop if done checking new version + break; + } + + display->SetStatus(Lang::Strings::ACTIVATION); + // Activation code is shown to the user and waiting for the user to input + if (ota.HasActivationCode()) { + ShowActivationCode(ota.GetActivationCode(), ota.GetActivationMessage()); + } + + // This will block the loop until the activation is done or timeout + for (int i = 0; i < 10; ++i) { + ESP_LOGI(TAG, "Activating... %d/%d", i + 1, 10); + esp_err_t err = ota.Activate(); + if (err == ESP_OK) { + xEventGroupSetBits(event_group_, MAIN_EVENT_CHECK_NEW_VERSION_DONE); + break; + } else if (err == ESP_ERR_TIMEOUT) { + vTaskDelay(pdMS_TO_TICKS(3000)); + } else { + vTaskDelay(pdMS_TO_TICKS(10000)); + } + if (device_state_ == kDeviceStateIdle) { + break; + } + } + } +} + +void Application::ShowActivationCode(const std::string& code, const std::string& message) { + struct digit_sound { + char digit; + const std::string_view& sound; + }; + static const std::array digit_sounds{{ + digit_sound{'0', Lang::Sounds::OGG_0}, + digit_sound{'1', Lang::Sounds::OGG_1}, + digit_sound{'2', Lang::Sounds::OGG_2}, + digit_sound{'3', Lang::Sounds::OGG_3}, + digit_sound{'4', Lang::Sounds::OGG_4}, + digit_sound{'5', Lang::Sounds::OGG_5}, + digit_sound{'6', Lang::Sounds::OGG_6}, + digit_sound{'7', Lang::Sounds::OGG_7}, + digit_sound{'8', Lang::Sounds::OGG_8}, + digit_sound{'9', Lang::Sounds::OGG_9} + }}; + + // This sentence uses 9KB of SRAM, so we need to wait for it to finish + Alert(Lang::Strings::ACTIVATION, message.c_str(), "link", Lang::Sounds::OGG_ACTIVATION); + + for (const auto& digit : code) { + auto it = std::find_if(digit_sounds.begin(), digit_sounds.end(), + [digit](const digit_sound& ds) { return ds.digit == digit; }); + if (it != digit_sounds.end()) { + audio_service_.PlaySound(it->sound); + } + } +} + +void Application::Alert(const char* status, const char* message, const char* emotion, const std::string_view& sound) { + ESP_LOGW(TAG, "Alert [%s] %s: %s", emotion, status, message); + auto display = Board::GetInstance().GetDisplay(); + display->SetStatus(status); + display->SetEmotion(emotion); + // Alert 时将情绪字符串(如 "happy"、"neutral")发送给 RP2040 触发对应舵机动画 + uart_send_string(emotion); + display->SetChatMessage("system", message); + if (!sound.empty()) { + audio_service_.PlaySound(sound); + } +} + +void Application::DismissAlert() { + if (device_state_ == kDeviceStateIdle) { + auto display = Board::GetInstance().GetDisplay(); + display->SetStatus(Lang::Strings::STANDBY); + display->SetEmotion("neutral"); + uart_send_string("idle"); + display->SetChatMessage("system", ""); + } +} + +void Application::ToggleChatState() { + if (device_state_ == kDeviceStateActivating) { + SetDeviceState(kDeviceStateIdle); + return; + } else if (device_state_ == kDeviceStateWifiConfiguring) { + audio_service_.EnableAudioTesting(true); + SetDeviceState(kDeviceStateAudioTesting); + return; + } else if (device_state_ == kDeviceStateAudioTesting) { + audio_service_.EnableAudioTesting(false); + SetDeviceState(kDeviceStateWifiConfiguring); + return; + } + + if (!protocol_) { + ESP_LOGE(TAG, "Protocol not initialized"); + return; + } + + if (device_state_ == kDeviceStateIdle) { + Schedule([this]() { + if (!protocol_->IsAudioChannelOpened()) { + SetDeviceState(kDeviceStateConnecting); + if (!protocol_->OpenAudioChannel()) { + return; + } + } + + SetListeningMode(aec_mode_ == kAecOff ? kListeningModeAutoStop : kListeningModeRealtime); + }); + } else if (device_state_ == kDeviceStateSpeaking) { + Schedule([this]() { + AbortSpeaking(kAbortReasonNone); + }); + } else if (device_state_ == kDeviceStateListening) { + Schedule([this]() { + protocol_->CloseAudioChannel(); + }); + } +} + +void Application::StartListening() { + if (device_state_ == kDeviceStateActivating) { + SetDeviceState(kDeviceStateIdle); + return; + } else if (device_state_ == kDeviceStateWifiConfiguring) { + audio_service_.EnableAudioTesting(true); + SetDeviceState(kDeviceStateAudioTesting); + return; + } + + if (!protocol_) { + ESP_LOGE(TAG, "Protocol not initialized"); + return; + } + + if (device_state_ == kDeviceStateIdle) { + Schedule([this]() { + if (!protocol_->IsAudioChannelOpened()) { + SetDeviceState(kDeviceStateConnecting); + if (!protocol_->OpenAudioChannel()) { + return; + } + } + + SetListeningMode(kListeningModeManualStop); + }); + } else if (device_state_ == kDeviceStateSpeaking) { + Schedule([this]() { + AbortSpeaking(kAbortReasonNone); + SetListeningMode(kListeningModeManualStop); + }); + } +} + +void Application::StopListening() { + if (device_state_ == kDeviceStateAudioTesting) { + audio_service_.EnableAudioTesting(false); + SetDeviceState(kDeviceStateWifiConfiguring); + return; + } + + const std::array valid_states = { + kDeviceStateListening, + kDeviceStateSpeaking, + kDeviceStateIdle, + }; + // If not valid, do nothing + if (std::find(valid_states.begin(), valid_states.end(), device_state_) == valid_states.end()) { + return; + } + + Schedule([this]() { + if (device_state_ == kDeviceStateListening) { + protocol_->SendStopListening(); + SetDeviceState(kDeviceStateIdle); + } + }); +} + +void Application::Start() { + auto& board = Board::GetInstance(); + SetDeviceState(kDeviceStateStarting); + + /* Setup the display */ + auto display = board.GetDisplay(); + + // Print board name/version info + display->SetChatMessage("system", SystemInfo::GetUserAgent().c_str()); + + /* Setup the audio service */ + auto codec = board.GetAudioCodec(); + audio_service_.Initialize(codec); + audio_service_.Start(); + + AudioServiceCallbacks callbacks; + callbacks.on_send_queue_available = [this]() { + xEventGroupSetBits(event_group_, MAIN_EVENT_SEND_AUDIO); + }; + callbacks.on_wake_word_detected = [this](const std::string& wake_word) { + xEventGroupSetBits(event_group_, MAIN_EVENT_WAKE_WORD_DETECTED); + }; + callbacks.on_vad_change = [this](bool speaking) { + xEventGroupSetBits(event_group_, MAIN_EVENT_VAD_CHANGE); + }; + audio_service_.SetCallbacks(callbacks); + + // Start the main event loop task with priority 3 + xTaskCreate([](void* arg) { + ((Application*)arg)->MainEventLoop(); + vTaskDelete(NULL); + }, "main_event_loop", 2048 * 4, this, 3, &main_event_loop_task_handle_); + + /* Start the clock timer to update the status bar */ + esp_timer_start_periodic(clock_timer_handle_, 1000000); + + /* Wait for the network to be ready */ + board.StartNetwork(); + + // Update the status bar immediately to show the network state + display->UpdateStatusBar(true); + + // Check for new assets version + CheckAssetsVersion(); + + // Check for new firmware version or get the MQTT broker address + Ota ota; + CheckNewVersion(ota); + + // Initialize the protocol + display->SetStatus(Lang::Strings::LOADING_PROTOCOL); + + // Add MCP common tools before initializing the protocol + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddCommonTools(); + mcp_server.AddUserOnlyTools(); + + if (ota.HasMqttConfig()) { + protocol_ = std::make_unique(); + } else if (ota.HasWebsocketConfig()) { + protocol_ = std::make_unique(); + } else { + ESP_LOGW(TAG, "No protocol specified in the OTA config, using MQTT"); + protocol_ = std::make_unique(); + } + + protocol_->OnConnected([this]() { + DismissAlert(); + }); + + protocol_->OnNetworkError([this](const std::string& message) { + last_error_message_ = message; + xEventGroupSetBits(event_group_, MAIN_EVENT_ERROR); + }); + protocol_->OnIncomingAudio([this](std::unique_ptr packet) { + if (device_state_ == kDeviceStateSpeaking) { + audio_service_.PushPacketToDecodeQueue(std::move(packet)); + } + }); + protocol_->OnAudioChannelOpened([this, codec, &board]() { + board.SetPowerSaveMode(false); + if (protocol_->server_sample_rate() != codec->output_sample_rate()) { + ESP_LOGW(TAG, "Server sample rate %d does not match device output sample rate %d, resampling may cause distortion", + protocol_->server_sample_rate(), codec->output_sample_rate()); + } + }); + protocol_->OnAudioChannelClosed([this, &board]() { + board.SetPowerSaveMode(true); + Schedule([this]() { + auto display = Board::GetInstance().GetDisplay(); + display->SetChatMessage("system", ""); + SetDeviceState(kDeviceStateIdle); + }); + }); + protocol_->OnIncomingJson([this, display](const cJSON* root) { + // Parse JSON data + auto type = cJSON_GetObjectItem(root, "type"); + if (strcmp(type->valuestring, "tts") == 0) { + auto state = cJSON_GetObjectItem(root, "state"); + if (strcmp(state->valuestring, "start") == 0) { + Schedule([this]() { + aborted_ = false; + if (device_state_ == kDeviceStateIdle || device_state_ == kDeviceStateListening) { + SetDeviceState(kDeviceStateSpeaking); + } + }); + } else if (strcmp(state->valuestring, "stop") == 0) { + Schedule([this]() { + if (device_state_ == kDeviceStateSpeaking) { + if (listening_mode_ == kListeningModeManualStop) { + SetDeviceState(kDeviceStateIdle); + } else { + SetDeviceState(kDeviceStateListening); + } + } + }); + } else if (strcmp(state->valuestring, "sentence_start") == 0) { + auto text = cJSON_GetObjectItem(root, "text"); + if (cJSON_IsString(text)) { + ESP_LOGI(TAG, "<< %s", text->valuestring); + Schedule([this, display, message = std::string(text->valuestring)]() { + display->SetChatMessage("assistant", message.c_str()); + }); + } + } + } else if (strcmp(type->valuestring, "stt") == 0) { + auto text = cJSON_GetObjectItem(root, "text"); + if (cJSON_IsString(text)) { + ESP_LOGI(TAG, ">> %s", text->valuestring); + Schedule([this, display, message = std::string(text->valuestring)]() { + display->SetChatMessage("user", message.c_str()); + }); + } + } else if (strcmp(type->valuestring, "llm") == 0) { + // LLM 回复中携带的情绪标签(如 "happy"、"thinking") + auto emotion = cJSON_GetObjectItem(root, "emotion"); + if (cJSON_IsString(emotion)) { + Schedule([this, display, emotion_str = std::string(emotion->valuestring)]() { + display->SetEmotion(emotion_str.c_str()); + // 将 AI 返回的情绪标签发送给 RP2040,实时切换舵机动画表情 + uart_send_string(emotion_str.c_str()); + }); + } + } else if (strcmp(type->valuestring, "mcp") == 0) { + auto payload = cJSON_GetObjectItem(root, "payload"); + if (cJSON_IsObject(payload)) { + McpServer::GetInstance().ParseMessage(payload); + } + } else if (strcmp(type->valuestring, "system") == 0) { + auto command = cJSON_GetObjectItem(root, "command"); + if (cJSON_IsString(command)) { + ESP_LOGI(TAG, "System command: %s", command->valuestring); + if (strcmp(command->valuestring, "reboot") == 0) { + // Do a reboot if user requests a OTA update + Schedule([this]() { + Reboot(); + }); + } else { + ESP_LOGW(TAG, "Unknown system command: %s", command->valuestring); + } + } + } else if (strcmp(type->valuestring, "alert") == 0) { + auto status = cJSON_GetObjectItem(root, "status"); + auto message = cJSON_GetObjectItem(root, "message"); + auto emotion = cJSON_GetObjectItem(root, "emotion"); + if (cJSON_IsString(status) && cJSON_IsString(message) && cJSON_IsString(emotion)) { + Alert(status->valuestring, message->valuestring, emotion->valuestring, Lang::Sounds::OGG_VIBRATION); + } else { + ESP_LOGW(TAG, "Alert command requires status, message and emotion"); + } +#if CONFIG_RECEIVE_CUSTOM_MESSAGE + } else if (strcmp(type->valuestring, "custom") == 0) { + auto payload = cJSON_GetObjectItem(root, "payload"); + ESP_LOGI(TAG, "Received custom message: %s", cJSON_PrintUnformatted(root)); + if (cJSON_IsObject(payload)) { + Schedule([this, display, payload_str = std::string(cJSON_PrintUnformatted(payload))]() { + display->SetChatMessage("system", payload_str.c_str()); + }); + } else { + ESP_LOGW(TAG, "Invalid custom message format: missing payload"); + } +#endif + } else { + ESP_LOGW(TAG, "Unknown message type: %s", type->valuestring); + } + }); + bool protocol_started = protocol_->Start(); + + SystemInfo::PrintHeapStats(); + SetDeviceState(kDeviceStateIdle); + + has_server_time_ = ota.HasServerTime(); + if (protocol_started) { + std::string message = std::string(Lang::Strings::VERSION) + ota.GetCurrentVersion(); + display->ShowNotification(message.c_str()); + display->SetChatMessage("system", ""); + // Play the success sound to indicate the device is ready + audio_service_.PlaySound(Lang::Sounds::OGG_SUCCESS); + } +} + +// Add a async task to MainLoop +void Application::Schedule(std::function callback) { + { + std::lock_guard lock(mutex_); + main_tasks_.push_back(std::move(callback)); + } + xEventGroupSetBits(event_group_, MAIN_EVENT_SCHEDULE); +} + +// The Main Event Loop controls the chat state and websocket connection +// If other tasks need to access the websocket or chat state, +// they should use Schedule to call this function +void Application::MainEventLoop() { + while (true) { + auto bits = xEventGroupWaitBits(event_group_, MAIN_EVENT_SCHEDULE | + MAIN_EVENT_SEND_AUDIO | + MAIN_EVENT_WAKE_WORD_DETECTED | + MAIN_EVENT_VAD_CHANGE | + MAIN_EVENT_CLOCK_TICK | + MAIN_EVENT_ERROR, pdTRUE, pdFALSE, portMAX_DELAY); + + if (bits & MAIN_EVENT_ERROR) { + SetDeviceState(kDeviceStateIdle); + Alert(Lang::Strings::ERROR, last_error_message_.c_str(), "circle_xmark", Lang::Sounds::OGG_EXCLAMATION); + } + + if (bits & MAIN_EVENT_SEND_AUDIO) { + while (auto packet = audio_service_.PopPacketFromSendQueue()) { + if (protocol_ && !protocol_->SendAudio(std::move(packet))) { + break; + } + } + } + + if (bits & MAIN_EVENT_WAKE_WORD_DETECTED) { + OnWakeWordDetected(); + } + + if (bits & MAIN_EVENT_VAD_CHANGE) { + if (device_state_ == kDeviceStateListening) { + auto led = Board::GetInstance().GetLed(); + led->OnStateChanged(); + } + } + + if (bits & MAIN_EVENT_SCHEDULE) { + std::unique_lock lock(mutex_); + auto tasks = std::move(main_tasks_); + lock.unlock(); + for (auto& task : tasks) { + task(); + } + } + + if (bits & MAIN_EVENT_CLOCK_TICK) { + clock_ticks_++; + auto display = Board::GetInstance().GetDisplay(); + display->UpdateStatusBar(); + + // Print the debug info every 10 seconds + if (clock_ticks_ % 10 == 0) { + // SystemInfo::PrintTaskCpuUsage(pdMS_TO_TICKS(1000)); + // SystemInfo::PrintTaskList(); + SystemInfo::PrintHeapStats(); + } + } + } +} + +void Application::OnWakeWordDetected() { + if (!protocol_) { + return; + } + + if (device_state_ == kDeviceStateIdle) { + audio_service_.EncodeWakeWord(); + + if (!protocol_->IsAudioChannelOpened()) { + SetDeviceState(kDeviceStateConnecting); + if (!protocol_->OpenAudioChannel()) { + audio_service_.EnableWakeWordDetection(true); + return; + } + } + + auto wake_word = audio_service_.GetLastWakeWord(); + ESP_LOGI(TAG, "Wake word detected: %s", wake_word.c_str()); +#if CONFIG_SEND_WAKE_WORD_DATA + // Encode and send the wake word data to the server + while (auto packet = audio_service_.PopWakeWordPacket()) { + protocol_->SendAudio(std::move(packet)); + } + // Set the chat state to wake word detected + protocol_->SendWakeWordDetected(wake_word); + SetListeningMode(aec_mode_ == kAecOff ? kListeningModeAutoStop : kListeningModeRealtime); +#else + SetListeningMode(aec_mode_ == kAecOff ? kListeningModeAutoStop : kListeningModeRealtime); + // Play the pop up sound to indicate the wake word is detected + audio_service_.PlaySound(Lang::Sounds::OGG_POPUP); +#endif + } else if (device_state_ == kDeviceStateSpeaking) { + AbortSpeaking(kAbortReasonWakeWordDetected); + } else if (device_state_ == kDeviceStateActivating) { + SetDeviceState(kDeviceStateIdle); + } +} + +void Application::AbortSpeaking(AbortReason reason) { + ESP_LOGI(TAG, "Abort speaking"); + aborted_ = true; + if (protocol_) { + protocol_->SendAbortSpeaking(reason); + } +} + +void Application::SetListeningMode(ListeningMode mode) { + listening_mode_ = mode; + SetDeviceState(kDeviceStateListening); +} + +void Application::SetDeviceState(DeviceState state) { + if (device_state_ == state) { + return; + } + + clock_ticks_ = 0; + auto previous_state = device_state_; + device_state_ = state; + ESP_LOGI(TAG, "STATE: %s", STATE_STRINGS[device_state_]); + + // Send the state change event + DeviceStateEventManager::GetInstance().PostStateChangeEvent(previous_state, state); + + auto& board = Board::GetInstance(); + auto display = board.GetDisplay(); + auto led = board.GetLed(); + led->OnStateChanged(); + // 根据设备状态通过 UART 发送指令给 RP2040,驱动舵机执行对应动画 + switch (state) { + case kDeviceStateUnknown: + case kDeviceStateIdle: + display->SetStatus(Lang::Strings::STANDBY); + display->SetEmotion("neutral"); + audio_service_.EnableVoiceProcessing(false); + audio_service_.EnableWakeWordDetection(true); + uart_send_string("idle"); // → RP2040: 进入睡眠姿态(闭眼、耳朵收起) + break; + case kDeviceStateConnecting: + display->SetStatus(Lang::Strings::CONNECTING); + display->SetEmotion("neutral"); + display->SetChatMessage("system", ""); + break; + case kDeviceStateListening: + display->SetStatus(Lang::Strings::LISTENING); + display->SetEmotion("neutral"); + uart_send_string("listening"); // → RP2040: 进入聆听姿态(好奇歪头、眼球随机看) + + // Make sure the audio processor is running + if (!audio_service_.IsAudioProcessorRunning()) { + // Send the start listening command + protocol_->SendStartListening(listening_mode_); + audio_service_.EnableVoiceProcessing(true); + audio_service_.EnableWakeWordDetection(false); + } + break; + case kDeviceStateSpeaking: + display->SetStatus(Lang::Strings::SPEAKING); + uart_send_string("speaking"); // → RP2040: 进入说话姿态(嘴巴开合、眼球随机看、身体摆动) + if (listening_mode_ != kListeningModeRealtime) { + audio_service_.EnableVoiceProcessing(false); + // Only AFE wake word can be detected in speaking mode + audio_service_.EnableWakeWordDetection(audio_service_.IsAfeWakeWord()); + } + audio_service_.ResetDecoder(); + break; + default: + // Do nothing + break; + } +} + +void Application::Reboot() { + ESP_LOGI(TAG, "Rebooting..."); + // Disconnect the audio channel + if (protocol_ && protocol_->IsAudioChannelOpened()) { + protocol_->CloseAudioChannel(); + } + protocol_.reset(); + audio_service_.Stop(); + + vTaskDelay(pdMS_TO_TICKS(1000)); + esp_restart(); +} + +bool Application::UpgradeFirmware(Ota& ota, const std::string& url) { + auto& board = Board::GetInstance(); + auto display = board.GetDisplay(); + + // Use provided URL or get from OTA object + std::string upgrade_url = url.empty() ? ota.GetFirmwareUrl() : url; + std::string version_info = url.empty() ? ota.GetFirmwareVersion() : "(Manual upgrade)"; + + // Close audio channel if it's open + if (protocol_ && protocol_->IsAudioChannelOpened()) { + ESP_LOGI(TAG, "Closing audio channel before firmware upgrade"); + protocol_->CloseAudioChannel(); + } + ESP_LOGI(TAG, "Starting firmware upgrade from URL: %s", upgrade_url.c_str()); + + Alert(Lang::Strings::OTA_UPGRADE, Lang::Strings::UPGRADING, "download", Lang::Sounds::OGG_UPGRADE); + vTaskDelay(pdMS_TO_TICKS(3000)); + + SetDeviceState(kDeviceStateUpgrading); + + std::string message = std::string(Lang::Strings::NEW_VERSION) + version_info; + display->SetChatMessage("system", message.c_str()); + + board.SetPowerSaveMode(false); + audio_service_.Stop(); + vTaskDelay(pdMS_TO_TICKS(1000)); + + bool upgrade_success = ota.StartUpgradeFromUrl(upgrade_url, [display](int progress, size_t speed) { + std::thread([display, progress, speed]() { + char buffer[32]; + snprintf(buffer, sizeof(buffer), "%d%% %uKB/s", progress, speed / 1024); + display->SetChatMessage("system", buffer); + }).detach(); + }); + + if (!upgrade_success) { + // Upgrade failed, restart audio service and continue running + ESP_LOGE(TAG, "Firmware upgrade failed, restarting audio service and continuing operation..."); + audio_service_.Start(); // Restart audio service + board.SetPowerSaveMode(true); // Restore power save mode + Alert(Lang::Strings::ERROR, Lang::Strings::UPGRADE_FAILED, "circle_xmark", Lang::Sounds::OGG_EXCLAMATION); + vTaskDelay(pdMS_TO_TICKS(3000)); + return false; + } else { + // Upgrade success, reboot immediately + ESP_LOGI(TAG, "Firmware upgrade successful, rebooting..."); + display->SetChatMessage("system", "Upgrade successful, rebooting..."); + vTaskDelay(pdMS_TO_TICKS(1000)); // Brief pause to show message + Reboot(); + return true; + } +} + +void Application::WakeWordInvoke(const std::string& wake_word) { + if (!protocol_) { + return; + } + + if (device_state_ == kDeviceStateIdle) { + audio_service_.EncodeWakeWord(); + + if (!protocol_->IsAudioChannelOpened()) { + SetDeviceState(kDeviceStateConnecting); + if (!protocol_->OpenAudioChannel()) { + audio_service_.EnableWakeWordDetection(true); + return; + } + } + + ESP_LOGI(TAG, "Wake word detected: %s", wake_word.c_str()); +#if CONFIG_USE_AFE_WAKE_WORD || CONFIG_USE_CUSTOM_WAKE_WORD + // Encode and send the wake word data to the server + while (auto packet = audio_service_.PopWakeWordPacket()) { + protocol_->SendAudio(std::move(packet)); + } + // Set the chat state to wake word detected + protocol_->SendWakeWordDetected(wake_word); + SetListeningMode(aec_mode_ == kAecOff ? kListeningModeAutoStop : kListeningModeRealtime); +#else + SetListeningMode(aec_mode_ == kAecOff ? kListeningModeAutoStop : kListeningModeRealtime); + // Play the pop up sound to indicate the wake word is detected + audio_service_.PlaySound(Lang::Sounds::OGG_POPUP); +#endif + } else if (device_state_ == kDeviceStateSpeaking) { + Schedule([this]() { + AbortSpeaking(kAbortReasonNone); + }); + } else if (device_state_ == kDeviceStateListening) { + Schedule([this]() { + if (protocol_) { + protocol_->CloseAudioChannel(); + } + }); + } +} + +bool Application::CanEnterSleepMode() { + if (device_state_ != kDeviceStateIdle) { + return false; + } + + if (protocol_ && protocol_->IsAudioChannelOpened()) { + return false; + } + + if (!audio_service_.IsIdle()) { + return false; + } + + // Now it is safe to enter sleep mode + return true; +} + +void Application::SendMcpMessage(const std::string& payload) { + if (protocol_ == nullptr) { + return; + } + + // Make sure you are using main thread to send MCP message + if (xTaskGetCurrentTaskHandle() == main_event_loop_task_handle_) { + protocol_->SendMcpMessage(payload); + } else { + Schedule([this, payload = std::move(payload)]() { + protocol_->SendMcpMessage(payload); + }); + } +} + +void Application::SetAecMode(AecMode mode) { + aec_mode_ = mode; + Schedule([this]() { + auto& board = Board::GetInstance(); + auto display = board.GetDisplay(); + switch (aec_mode_) { + case kAecOff: + audio_service_.EnableDeviceAec(false); + display->ShowNotification(Lang::Strings::RTC_MODE_OFF); + break; + case kAecOnServerSide: + audio_service_.EnableDeviceAec(false); + display->ShowNotification(Lang::Strings::RTC_MODE_ON); + break; + case kAecOnDeviceSide: + audio_service_.EnableDeviceAec(true); + display->ShowNotification(Lang::Strings::RTC_MODE_ON); + break; + } + + // If the AEC mode is changed, close the audio channel + if (protocol_ && protocol_->IsAudioChannelOpened()) { + protocol_->CloseAudioChannel(); + } + }); +} + +void Application::PlaySound(const std::string_view& sound) { + audio_service_.PlaySound(sound); +} \ No newline at end of file diff --git a/main/application.h b/main/application.h new file mode 100644 index 0000000..bff4e9e --- /dev/null +++ b/main/application.h @@ -0,0 +1,110 @@ +#ifndef _APPLICATION_H_ +#define _APPLICATION_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "protocol.h" +#include "ota.h" +#include "audio_service.h" +#include "device_state_event.h" + + +#define MAIN_EVENT_SCHEDULE (1 << 0) +#define MAIN_EVENT_SEND_AUDIO (1 << 1) +#define MAIN_EVENT_WAKE_WORD_DETECTED (1 << 2) +#define MAIN_EVENT_VAD_CHANGE (1 << 3) +#define MAIN_EVENT_ERROR (1 << 4) +#define MAIN_EVENT_CHECK_NEW_VERSION_DONE (1 << 5) +#define MAIN_EVENT_CLOCK_TICK (1 << 6) + + +enum AecMode { + kAecOff, + kAecOnDeviceSide, + kAecOnServerSide, +}; + +class Application { +public: + static Application& GetInstance() { + static Application instance; + return instance; + } + // 删除拷贝构造函数和赋值运算符 + Application(const Application&) = delete; + Application& operator=(const Application&) = delete; + + void Start(); + void MainEventLoop(); + DeviceState GetDeviceState() const { return device_state_; } + bool IsVoiceDetected() const { return audio_service_.IsVoiceDetected(); } + void Schedule(std::function callback); + void SetDeviceState(DeviceState state); + void Alert(const char* status, const char* message, const char* emotion = "", const std::string_view& sound = ""); + void DismissAlert(); + void AbortSpeaking(AbortReason reason); + void ToggleChatState(); + void StartListening(); + void StopListening(); + void Reboot(); + void WakeWordInvoke(const std::string& wake_word); + bool UpgradeFirmware(Ota& ota, const std::string& url = ""); + bool CanEnterSleepMode(); + void SendMcpMessage(const std::string& payload); + void SetAecMode(AecMode mode); + AecMode GetAecMode() const { return aec_mode_; } + void PlaySound(const std::string_view& sound); + AudioService& GetAudioService() { return audio_service_; } + +private: + Application(); + ~Application(); + + std::mutex mutex_; + std::deque> main_tasks_; + std::unique_ptr protocol_; + EventGroupHandle_t event_group_ = nullptr; + esp_timer_handle_t clock_timer_handle_ = nullptr; + volatile DeviceState device_state_ = kDeviceStateUnknown; + ListeningMode listening_mode_ = kListeningModeAutoStop; + AecMode aec_mode_ = kAecOff; + std::string last_error_message_; + AudioService audio_service_; + + bool has_server_time_ = false; + bool aborted_ = false; + int clock_ticks_ = 0; + TaskHandle_t check_new_version_task_handle_ = nullptr; + TaskHandle_t main_event_loop_task_handle_ = nullptr; + + void OnWakeWordDetected(); + void CheckNewVersion(Ota& ota); + void CheckAssetsVersion(); + void ShowActivationCode(const std::string& code, const std::string& message); + void SetListeningMode(ListeningMode mode); +}; + + +class TaskPriorityReset { +public: + TaskPriorityReset(BaseType_t priority) { + original_priority_ = uxTaskPriorityGet(NULL); + vTaskPrioritySet(NULL, priority); + } + ~TaskPriorityReset() { + vTaskPrioritySet(NULL, original_priority_); + } + +private: + BaseType_t original_priority_; +}; + +#endif // _APPLICATION_H_ diff --git a/main/assets.cc b/main/assets.cc new file mode 100644 index 0000000..2d45bd3 --- /dev/null +++ b/main/assets.cc @@ -0,0 +1,532 @@ +#include "assets.h" +#include "board.h" +#include "display.h" +#include "application.h" +#include "lvgl_theme.h" +#include "emote_display.h" +#ifdef HAVE_LVGL +#include "display/lcd_display.h" +#endif + +#include +#include +#include +#include + + +#define TAG "Assets" + +struct mmap_assets_table { + char asset_name[32]; /*!< Name of the asset */ + uint32_t asset_size; /*!< Size of the asset */ + uint32_t asset_offset; /*!< Offset of the asset */ + uint16_t asset_width; /*!< Width of the asset */ + uint16_t asset_height; /*!< Height of the asset */ +}; + + +Assets::Assets() { + // Initialize the partition + InitializePartition(); +} + +Assets::~Assets() { + if (mmap_handle_ != 0) { + esp_partition_munmap(mmap_handle_); + } +} + +uint32_t Assets::CalculateChecksum(const char* data, uint32_t length) { + uint32_t checksum = 0; + for (uint32_t i = 0; i < length; i++) { + checksum += data[i]; + } + return checksum & 0xFFFF; +} + +bool Assets::InitializePartition() { + partition_valid_ = false; + checksum_valid_ = false; + assets_.clear(); + + partition_ = esp_partition_find_first(ESP_PARTITION_TYPE_ANY, ESP_PARTITION_SUBTYPE_ANY, "assets"); + if (partition_ == nullptr) { + ESP_LOGI(TAG, "No assets partition found"); + return false; + } + + int free_pages = spi_flash_mmap_get_free_pages(SPI_FLASH_MMAP_DATA); + uint32_t storage_size = free_pages * 64 * 1024; + ESP_LOGI(TAG, "The storage free size is %ld KB", storage_size / 1024); + ESP_LOGI(TAG, "The partition size is %ld KB", partition_->size / 1024); + if (storage_size < partition_->size) { + ESP_LOGE(TAG, "The free size %ld KB is less than assets partition required %ld KB", storage_size / 1024, partition_->size / 1024); + return false; + } + + esp_err_t err = esp_partition_mmap(partition_, 0, partition_->size, ESP_PARTITION_MMAP_DATA, (const void**)&mmap_root_, &mmap_handle_); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to mmap assets partition: %s", esp_err_to_name(err)); + return false; + } + + partition_valid_ = true; + + uint32_t stored_files = *(uint32_t*)(mmap_root_ + 0); + uint32_t stored_chksum = *(uint32_t*)(mmap_root_ + 4); + uint32_t stored_len = *(uint32_t*)(mmap_root_ + 8); + + if (stored_len > partition_->size - 12) { + ESP_LOGD(TAG, "The stored_len (0x%lx) is greater than the partition size (0x%lx) - 12", stored_len, partition_->size); + return false; + } + + auto start_time = esp_timer_get_time(); + uint32_t calculated_checksum = CalculateChecksum(mmap_root_ + 12, stored_len); + auto end_time = esp_timer_get_time(); + ESP_LOGI(TAG, "The checksum calculation time is %d ms", int((end_time - start_time) / 1000)); + + if (calculated_checksum != stored_chksum) { + ESP_LOGE(TAG, "The calculated checksum (0x%lx) does not match the stored checksum (0x%lx)", calculated_checksum, stored_chksum); + return false; + } + + checksum_valid_ = true; + + for (uint32_t i = 0; i < stored_files; i++) { + auto item = (const mmap_assets_table*)(mmap_root_ + 12 + i * sizeof(mmap_assets_table)); + auto asset = Asset{ + .size = static_cast(item->asset_size), + .offset = static_cast(12 + sizeof(mmap_assets_table) * stored_files + item->asset_offset) + }; + assets_[item->asset_name] = asset; + } + return checksum_valid_; +} + +bool Assets::Apply() { + void* ptr = nullptr; + size_t size = 0; + if (!GetAssetData("index.json", ptr, size)) { + ESP_LOGE(TAG, "The index.json file is not found"); + return false; + } + + cJSON* root = cJSON_ParseWithLength(static_cast(ptr), size); + if (root == nullptr) { + ESP_LOGE(TAG, "The index.json file is not valid"); + return false; + } + + cJSON* version = cJSON_GetObjectItem(root, "version"); + if (cJSON_IsNumber(version)) { + if (version->valuedouble > 1) { + ESP_LOGE(TAG, "The assets version %d is not supported, please upgrade the firmware", version->valueint); + return false; + } + } + + cJSON* srmodels = cJSON_GetObjectItem(root, "srmodels"); + if (cJSON_IsString(srmodels)) { + std::string srmodels_file = srmodels->valuestring; + if (GetAssetData(srmodels_file, ptr, size)) { + if (models_list_ != nullptr) { + esp_srmodel_deinit(models_list_); + models_list_ = nullptr; + } + models_list_ = srmodel_load(static_cast(ptr)); + if (models_list_ != nullptr) { + auto& app = Application::GetInstance(); + app.GetAudioService().SetModelsList(models_list_); + } else { + ESP_LOGE(TAG, "Failed to load srmodels.bin"); + } + } else { + ESP_LOGE(TAG, "The srmodels file %s is not found", srmodels_file.c_str()); + } + } + +#ifdef HAVE_LVGL + auto& theme_manager = LvglThemeManager::GetInstance(); + auto light_theme = theme_manager.GetTheme("light"); + auto dark_theme = theme_manager.GetTheme("dark"); + + cJSON* font = cJSON_GetObjectItem(root, "text_font"); + if (cJSON_IsString(font)) { + std::string fonts_text_file = font->valuestring; + if (GetAssetData(fonts_text_file, ptr, size)) { + auto text_font = std::make_shared(ptr); + if (text_font->font() == nullptr) { + ESP_LOGE(TAG, "Failed to load fonts.bin"); + return false; + } + if (light_theme != nullptr) { + light_theme->set_text_font(text_font); + } + if (dark_theme != nullptr) { + dark_theme->set_text_font(text_font); + } + } else { + ESP_LOGE(TAG, "The font file %s is not found", fonts_text_file.c_str()); + } + } + + cJSON* emoji_collection = cJSON_GetObjectItem(root, "emoji_collection"); + if (cJSON_IsArray(emoji_collection)) { + auto custom_emoji_collection = std::make_shared(); + int emoji_count = cJSON_GetArraySize(emoji_collection); + for (int i = 0; i < emoji_count; i++) { + cJSON* emoji = cJSON_GetArrayItem(emoji_collection, i); + if (cJSON_IsObject(emoji)) { + cJSON* name = cJSON_GetObjectItem(emoji, "name"); + cJSON* file = cJSON_GetObjectItem(emoji, "file"); + cJSON* eaf = cJSON_GetObjectItem(emoji, "eaf"); + if (cJSON_IsString(name) && cJSON_IsString(file) && (NULL== eaf)) { + if (!GetAssetData(file->valuestring, ptr, size)) { + ESP_LOGE(TAG, "Emoji %s image file %s is not found", name->valuestring, file->valuestring); + continue; + } + custom_emoji_collection->AddEmoji(name->valuestring, new LvglRawImage(ptr, size)); + } + } + } + if (light_theme != nullptr) { + light_theme->set_emoji_collection(custom_emoji_collection); + } + if (dark_theme != nullptr) { + dark_theme->set_emoji_collection(custom_emoji_collection); + } + } + + cJSON* skin = cJSON_GetObjectItem(root, "skin"); + if (cJSON_IsObject(skin)) { + cJSON* light_skin = cJSON_GetObjectItem(skin, "light"); + if (cJSON_IsObject(light_skin) && light_theme != nullptr) { + cJSON* text_color = cJSON_GetObjectItem(light_skin, "text_color"); + cJSON* background_color = cJSON_GetObjectItem(light_skin, "background_color"); + cJSON* background_image = cJSON_GetObjectItem(light_skin, "background_image"); + if (cJSON_IsString(text_color)) { + light_theme->set_text_color(LvglTheme::ParseColor(text_color->valuestring)); + } + if (cJSON_IsString(background_color)) { + light_theme->set_background_color(LvglTheme::ParseColor(background_color->valuestring)); + light_theme->set_chat_background_color(LvglTheme::ParseColor(background_color->valuestring)); + } + if (cJSON_IsString(background_image)) { + if (!GetAssetData(background_image->valuestring, ptr, size)) { + ESP_LOGE(TAG, "The background image file %s is not found", background_image->valuestring); + return false; + } + auto background_image = std::make_shared(ptr); + light_theme->set_background_image(background_image); + } + } + cJSON* dark_skin = cJSON_GetObjectItem(skin, "dark"); + if (cJSON_IsObject(dark_skin) && dark_theme != nullptr) { + cJSON* text_color = cJSON_GetObjectItem(dark_skin, "text_color"); + cJSON* background_color = cJSON_GetObjectItem(dark_skin, "background_color"); + cJSON* background_image = cJSON_GetObjectItem(dark_skin, "background_image"); + if (cJSON_IsString(text_color)) { + dark_theme->set_text_color(LvglTheme::ParseColor(text_color->valuestring)); + } + if (cJSON_IsString(background_color)) { + dark_theme->set_background_color(LvglTheme::ParseColor(background_color->valuestring)); + dark_theme->set_chat_background_color(LvglTheme::ParseColor(background_color->valuestring)); + } + if (cJSON_IsString(background_image)) { + if (!GetAssetData(background_image->valuestring, ptr, size)) { + ESP_LOGE(TAG, "The background image file %s is not found", background_image->valuestring); + return false; + } + auto background_image = std::make_shared(ptr); + dark_theme->set_background_image(background_image); + } + } + } + + auto display = Board::GetInstance().GetDisplay(); + ESP_LOGI(TAG, "Refreshing display theme..."); + + auto current_theme = display->GetTheme(); + if (current_theme != nullptr) { + display->SetTheme(current_theme); + } + + // Parse hide_subtitle configuration + cJSON* hide_subtitle = cJSON_GetObjectItem(root, "hide_subtitle"); + if (cJSON_IsBool(hide_subtitle)) { + bool hide = cJSON_IsTrue(hide_subtitle); + auto lcd_display = dynamic_cast(display); + if (lcd_display != nullptr) { + lcd_display->SetHideSubtitle(hide); + ESP_LOGI(TAG, "Set hide_subtitle to %s", hide ? "true" : "false"); + } + } + +#elif defined(CONFIG_USE_EMOTE_MESSAGE_STYLE) + auto &board = Board::GetInstance(); + auto display = board.GetDisplay(); + auto emote_display = dynamic_cast(display); + + cJSON* font = cJSON_GetObjectItem(root, "text_font"); + if (cJSON_IsString(font)) { + std::string fonts_text_file = font->valuestring; + if (GetAssetData(fonts_text_file, ptr, size)) { + auto text_font = std::make_shared(ptr); + if (text_font->font() == nullptr) { + ESP_LOGE(TAG, "Failed to load fonts.bin"); + return false; + } + + if (emote_display) { + emote_display->AddTextFont(text_font); + } + } else { + ESP_LOGE(TAG, "The font file %s is not found", fonts_text_file.c_str()); + } + } + + cJSON* emoji_collection = cJSON_GetObjectItem(root, "emoji_collection"); + if (cJSON_IsArray(emoji_collection)) { + int emoji_count = cJSON_GetArraySize(emoji_collection); + if (emote_display) { + for (int i = 0; i < emoji_count; i++) { + cJSON* icon = cJSON_GetArrayItem(emoji_collection, i); + if (cJSON_IsObject(icon)) { + cJSON* name = cJSON_GetObjectItem(icon, "name"); + cJSON* file = cJSON_GetObjectItem(icon, "file"); + + if (cJSON_IsString(name) && cJSON_IsString(file)) { + if (GetAssetData(file->valuestring, ptr, size)) { + cJSON* eaf = cJSON_GetObjectItem(icon, "eaf"); + bool lack_value = false; + bool loop_value = false; + int fps_value = 0; + + if (cJSON_IsObject(eaf)) { + cJSON* lack = cJSON_GetObjectItem(eaf, "lack"); + cJSON* loop = cJSON_GetObjectItem(eaf, "loop"); + cJSON* fps = cJSON_GetObjectItem(eaf, "fps"); + + lack_value = lack ? cJSON_IsTrue(lack) : false; + loop_value = loop ? cJSON_IsTrue(loop) : false; + fps_value = fps ? fps->valueint : 0; + + emote_display->AddEmojiData(name->valuestring, ptr, size, + static_cast(fps_value), + loop_value, lack_value); + } + + } else { + ESP_LOGE(TAG, "Emoji \"%10s\" image file %s is not found", name->valuestring, file->valuestring); + } + } + } + } + } + } + + cJSON* icon_collection = cJSON_GetObjectItem(root, "icon_collection"); + if (cJSON_IsArray(icon_collection)) { + if (emote_display) { + int icon_count = cJSON_GetArraySize(icon_collection); + for (int i = 0; i < icon_count; i++) { + cJSON* icon = cJSON_GetArrayItem(icon_collection, i); + if (cJSON_IsObject(icon)) { + cJSON* name = cJSON_GetObjectItem(icon, "name"); + cJSON* file = cJSON_GetObjectItem(icon, "file"); + + if (cJSON_IsString(name) && cJSON_IsString(file)) { + if (GetAssetData(file->valuestring, ptr, size)) { + emote_display->AddIconData(name->valuestring, ptr, size); + } else { + ESP_LOGE(TAG, "Icon \"%10s\" image file %s is not found", name->valuestring, file->valuestring); + } + } + } + } + } + } + + cJSON* layout_json = cJSON_GetObjectItem(root, "layout"); + if (cJSON_IsArray(layout_json)) { + int layout_count = cJSON_GetArraySize(layout_json); + + for (int i = 0; i < layout_count; i++) { + cJSON* layout_item = cJSON_GetArrayItem(layout_json, i); + if (cJSON_IsObject(layout_item)) { + cJSON* name = cJSON_GetObjectItem(layout_item, "name"); + cJSON* align = cJSON_GetObjectItem(layout_item, "align"); + cJSON* x = cJSON_GetObjectItem(layout_item, "x"); + cJSON* y = cJSON_GetObjectItem(layout_item, "y"); + cJSON* width = cJSON_GetObjectItem(layout_item, "width"); + cJSON* height = cJSON_GetObjectItem(layout_item, "height"); + + if (cJSON_IsString(name) && cJSON_IsString(align) && cJSON_IsNumber(x) && cJSON_IsNumber(y)) { + int width_val = cJSON_IsNumber(width) ? width->valueint : 0; + int height_val = cJSON_IsNumber(height) ? height->valueint : 0; + + if (emote_display) { + emote_display->AddLayoutData(name->valuestring, align->valuestring, + x->valueint, y->valueint, width_val, height_val); + } + } else { + ESP_LOGW(TAG, "Invalid layout item %d: missing required fields", i); + } + } + } + } +#endif + + cJSON_Delete(root); + return true; +} + +bool Assets::Download(std::string url, std::function progress_callback) { + ESP_LOGI(TAG, "Downloading new version of assets from %s", url.c_str()); + + // 取消当前资源分区的内存映射 + if (mmap_handle_ != 0) { + esp_partition_munmap(mmap_handle_); + mmap_handle_ = 0; + mmap_root_ = nullptr; + } + checksum_valid_ = false; + assets_.clear(); + + // 下载新的资源文件 + auto network = Board::GetInstance().GetNetwork(); + auto http = network->CreateHttp(0); + + if (!http->Open("GET", url)) { + ESP_LOGE(TAG, "Failed to open HTTP connection"); + return false; + } + + if (http->GetStatusCode() != 200) { + ESP_LOGE(TAG, "Failed to get assets, status code: %d", http->GetStatusCode()); + return false; + } + + size_t content_length = http->GetBodyLength(); + if (content_length == 0) { + ESP_LOGE(TAG, "Failed to get content length"); + return false; + } + + if (content_length > partition_->size) { + ESP_LOGE(TAG, "Assets file size (%u) is larger than partition size (%lu)", content_length, partition_->size); + return false; + } + + // 定义扇区大小为4KB(ESP32的标准扇区大小) + const size_t SECTOR_SIZE = esp_partition_get_main_flash_sector_size(); + + // 计算需要擦除的扇区数量 + size_t sectors_to_erase = (content_length + SECTOR_SIZE - 1) / SECTOR_SIZE; // 向上取整 + size_t total_erase_size = sectors_to_erase * SECTOR_SIZE; + + ESP_LOGI(TAG, "Sector size: %u, content length: %u, sectors to erase: %u, total erase size: %u", + SECTOR_SIZE, content_length, sectors_to_erase, total_erase_size); + + // 写入新的资源文件到分区,一边erase一边写入 + char buffer[512]; + size_t total_written = 0; + size_t recent_written = 0; + size_t current_sector = 0; + auto last_calc_time = esp_timer_get_time(); + + while (true) { + int ret = http->Read(buffer, sizeof(buffer)); + if (ret < 0) { + ESP_LOGE(TAG, "Failed to read HTTP data: %s", esp_err_to_name(ret)); + return false; + } + + if (ret == 0) { + break; + } + + // 检查是否需要擦除新的扇区 + size_t write_end_offset = total_written + ret; + size_t needed_sectors = (write_end_offset + SECTOR_SIZE - 1) / SECTOR_SIZE; + + // 擦除需要的新扇区 + while (current_sector < needed_sectors) { + size_t sector_start = current_sector * SECTOR_SIZE; + size_t sector_end = (current_sector + 1) * SECTOR_SIZE; + + // 确保擦除范围不超过分区大小 + if (sector_end > partition_->size) { + ESP_LOGE(TAG, "Sector end (%u) exceeds partition size (%lu)", sector_end, partition_->size); + return false; + } + + ESP_LOGD(TAG, "Erasing sector %u (offset: %u, size: %u)", current_sector, sector_start, SECTOR_SIZE); + esp_err_t err = esp_partition_erase_range(partition_, sector_start, SECTOR_SIZE); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to erase sector %u at offset %u: %s", current_sector, sector_start, esp_err_to_name(err)); + return false; + } + + current_sector++; + } + + // 写入数据到分区 + esp_err_t err = esp_partition_write(partition_, total_written, buffer, ret); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to write to assets partition at offset %u: %s", total_written, esp_err_to_name(err)); + return false; + } + + total_written += ret; + recent_written += ret; + + // 计算进度和速度 + if (esp_timer_get_time() - last_calc_time >= 1000000 || total_written == content_length || ret == 0) { + size_t progress = total_written * 100 / content_length; + size_t speed = recent_written; // 每秒的字节数 + ESP_LOGI(TAG, "Progress: %u%% (%u/%u), Speed: %u B/s, Sectors erased: %u", + progress, total_written, content_length, speed, current_sector); + if (progress_callback) { + progress_callback(progress, speed); + } + last_calc_time = esp_timer_get_time(); + recent_written = 0; // 重置最近写入的字节数 + } + } + + http->Close(); + + if (total_written != content_length) { + ESP_LOGE(TAG, "Downloaded size (%u) does not match expected size (%u)", total_written, content_length); + return false; + } + + ESP_LOGI(TAG, "Assets download completed, total written: %u bytes, total sectors erased: %u", + total_written, current_sector); + + // 重新初始化资源分区 + if (!InitializePartition()) { + ESP_LOGE(TAG, "Failed to re-initialize assets partition"); + return false; + } + + return true; +} + +bool Assets::GetAssetData(const std::string& name, void*& ptr, size_t& size) { + auto asset = assets_.find(name); + if (asset == assets_.end()) { + return false; + } + auto data = (const char*)(mmap_root_ + asset->second.offset); + if (data[0] != 'Z' || data[1] != 'Z') { + ESP_LOGE(TAG, "The asset %s is not valid with magic %02x%02x", name.c_str(), data[0], data[1]); + return false; + } + + ptr = static_cast(const_cast(data + 2)); + size = asset->second.size; + return true; +} diff --git a/main/assets.h b/main/assets.h new file mode 100644 index 0000000..016692e --- /dev/null +++ b/main/assets.h @@ -0,0 +1,52 @@ +#ifndef ASSETS_H +#define ASSETS_H + +#include +#include +#include + +#include +#include +#include + + +struct Asset { + size_t size; + size_t offset; +}; + +class Assets { +public: + static Assets& GetInstance() { + static Assets instance; + return instance; + } + ~Assets(); + + bool Download(std::string url, std::function progress_callback); + bool Apply(); + bool GetAssetData(const std::string& name, void*& ptr, size_t& size); + + inline bool partition_valid() const { return partition_valid_; } + inline bool checksum_valid() const { return checksum_valid_; } + inline std::string default_assets_url() const { return default_assets_url_; } + +private: + Assets(); + Assets(const Assets&) = delete; + Assets& operator=(const Assets&) = delete; + + bool InitializePartition(); + uint32_t CalculateChecksum(const char* data, uint32_t length); + + const esp_partition_t* partition_ = nullptr; + esp_partition_mmap_handle_t mmap_handle_ = 0; + const char* mmap_root_ = nullptr; + bool partition_valid_ = false; + bool checksum_valid_ = false; + std::string default_assets_url_; + srmodel_list_t* models_list_ = nullptr; + std::map assets_; +}; + +#endif diff --git a/main/assets/common/exclamation.ogg b/main/assets/common/exclamation.ogg new file mode 100644 index 0000000..9a4cf58 Binary files /dev/null and b/main/assets/common/exclamation.ogg differ diff --git a/main/assets/common/low_battery.ogg b/main/assets/common/low_battery.ogg new file mode 100644 index 0000000..968b3ee Binary files /dev/null and b/main/assets/common/low_battery.ogg differ diff --git a/main/assets/common/popup.ogg b/main/assets/common/popup.ogg new file mode 100644 index 0000000..ea73b6f Binary files /dev/null and b/main/assets/common/popup.ogg differ diff --git a/main/assets/common/success.ogg b/main/assets/common/success.ogg new file mode 100644 index 0000000..ced1902 Binary files /dev/null and b/main/assets/common/success.ogg differ diff --git a/main/assets/common/vibration.ogg b/main/assets/common/vibration.ogg new file mode 100644 index 0000000..0076436 Binary files /dev/null and b/main/assets/common/vibration.ogg differ diff --git a/main/assets/locales/ar-SA/0.ogg b/main/assets/locales/ar-SA/0.ogg new file mode 100644 index 0000000..c656582 Binary files /dev/null and b/main/assets/locales/ar-SA/0.ogg differ diff --git a/main/assets/locales/ar-SA/1.ogg b/main/assets/locales/ar-SA/1.ogg new file mode 100644 index 0000000..dca3e06 Binary files /dev/null and b/main/assets/locales/ar-SA/1.ogg differ diff --git a/main/assets/locales/ar-SA/2.ogg b/main/assets/locales/ar-SA/2.ogg new file mode 100644 index 0000000..6d1f4d7 Binary files /dev/null and b/main/assets/locales/ar-SA/2.ogg differ diff --git a/main/assets/locales/ar-SA/3.ogg b/main/assets/locales/ar-SA/3.ogg new file mode 100644 index 0000000..12667d9 Binary files /dev/null and b/main/assets/locales/ar-SA/3.ogg differ diff --git a/main/assets/locales/ar-SA/4.ogg b/main/assets/locales/ar-SA/4.ogg new file mode 100644 index 0000000..e12dd7a Binary files /dev/null and b/main/assets/locales/ar-SA/4.ogg differ diff --git a/main/assets/locales/ar-SA/5.ogg b/main/assets/locales/ar-SA/5.ogg new file mode 100644 index 0000000..7dae30d Binary files /dev/null and b/main/assets/locales/ar-SA/5.ogg differ diff --git a/main/assets/locales/ar-SA/6.ogg b/main/assets/locales/ar-SA/6.ogg new file mode 100644 index 0000000..697278b Binary files /dev/null and b/main/assets/locales/ar-SA/6.ogg differ diff --git a/main/assets/locales/ar-SA/7.ogg b/main/assets/locales/ar-SA/7.ogg new file mode 100644 index 0000000..f83701d Binary files /dev/null and b/main/assets/locales/ar-SA/7.ogg differ diff --git a/main/assets/locales/ar-SA/8.ogg b/main/assets/locales/ar-SA/8.ogg new file mode 100644 index 0000000..bf3d2a1 Binary files /dev/null and b/main/assets/locales/ar-SA/8.ogg differ diff --git a/main/assets/locales/ar-SA/9.ogg b/main/assets/locales/ar-SA/9.ogg new file mode 100644 index 0000000..6d62228 Binary files /dev/null and b/main/assets/locales/ar-SA/9.ogg differ diff --git a/main/assets/locales/ar-SA/activation.ogg b/main/assets/locales/ar-SA/activation.ogg new file mode 100644 index 0000000..17aa008 Binary files /dev/null and b/main/assets/locales/ar-SA/activation.ogg differ diff --git a/main/assets/locales/ar-SA/err_pin.ogg b/main/assets/locales/ar-SA/err_pin.ogg new file mode 100644 index 0000000..8c624f5 Binary files /dev/null and b/main/assets/locales/ar-SA/err_pin.ogg differ diff --git a/main/assets/locales/ar-SA/err_reg.ogg b/main/assets/locales/ar-SA/err_reg.ogg new file mode 100644 index 0000000..b540a47 Binary files /dev/null and b/main/assets/locales/ar-SA/err_reg.ogg differ diff --git a/main/assets/locales/ar-SA/language.json b/main/assets/locales/ar-SA/language.json new file mode 100644 index 0000000..88263e4 --- /dev/null +++ b/main/assets/locales/ar-SA/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "ar-SA" + }, + "strings": { + "WARNING": "تحذير", + "INFO": "معلومات", + "ERROR": "خطأ", + "VERSION": "الإصدار ", + "LOADING_PROTOCOL": "الاتصال بالخادم...", + "INITIALIZING": "التهيئة...", + "PIN_ERROR": "يرجى إدخال بطاقة SIM", + "REG_ERROR": "لا يمكن الوصول إلى الشبكة، يرجى التحقق من حالة بطاقة البيانات", + "DETECTING_MODULE": "اكتشاف الوحدة...", + "REGISTERING_NETWORK": "انتظار الشبكة...", + "CHECKING_NEW_VERSION": "فحص الإصدار الجديد...", + "CHECK_NEW_VERSION_FAILED": "فشل فحص الإصدار الجديد، سيتم المحاولة خلال %d ثانية: %s", + "SWITCH_TO_WIFI_NETWORK": "التبديل إلى Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "التبديل إلى 4G...", + "STANDBY": "في الانتظار", + "CONNECT_TO": "الاتصال بـ ", + "CONNECTING": "جاري الاتصال...", + "CONNECTED_TO": "متصل بـ ", + "LISTENING": "الاستماع...", + "SPEAKING": "التحدث...", + "SERVER_NOT_FOUND": "البحث عن خدمة متاحة", + "SERVER_NOT_CONNECTED": "لا يمكن الاتصال بالخدمة، يرجى المحاولة لاحقاً", + "SERVER_TIMEOUT": "انتهت مهلة الاستجابة", + "SERVER_ERROR": "فشل الإرسال، يرجى التحقق من الشبكة", + "CONNECT_TO_HOTSPOT": "اتصل الهاتف بنقطة الاتصال ", + "ACCESS_VIA_BROWSER": "،الوصول عبر المتصفح ", + "WIFI_CONFIG_MODE": "وضع تكوين الشبكة", + "ENTERING_WIFI_CONFIG_MODE": "الدخول في وضع تكوين الشبكة...", + "SCANNING_WIFI": "فحص Wi-Fi...", + "NEW_VERSION": "إصدار جديد ", + "OTA_UPGRADE": "تحديث OTA", + "UPGRADING": "تحديث النظام...", + "UPGRADE_FAILED": "فشل التحديث", + "ACTIVATION": "تفعيل الجهاز", + "BATTERY_LOW": "البطارية منخفضة", + "BATTERY_CHARGING": "جاري الشحن", + "BATTERY_FULL": "البطارية ممتلئة", + "BATTERY_NEED_CHARGE": "البطارية منخفضة، يرجى الشحن", + "VOLUME": "الصوت ", + "MUTED": "صامت", + "MAX_VOLUME": "أقصى صوت", + "RTC_MODE_OFF": "AEC مُوقف", + "RTC_MODE_ON": "AEC مُشغل", + "DOWNLOAD_ASSETS_FAILED": "فشل في تنزيل الموارد", + "LOADING_ASSETS": "جاري تحميل الموارد...", + "PLEASE_WAIT": "يرجى الانتظار...", + "FOUND_NEW_ASSETS": "تم العثور على موارد جديدة: %s", + "HELLO_MY_FRIEND": "مرحباً، صديقي!" + } +} \ No newline at end of file diff --git a/main/assets/locales/ar-SA/upgrade.ogg b/main/assets/locales/ar-SA/upgrade.ogg new file mode 100644 index 0000000..f60d374 Binary files /dev/null and b/main/assets/locales/ar-SA/upgrade.ogg differ diff --git a/main/assets/locales/ar-SA/welcome.ogg b/main/assets/locales/ar-SA/welcome.ogg new file mode 100644 index 0000000..77028ad Binary files /dev/null and b/main/assets/locales/ar-SA/welcome.ogg differ diff --git a/main/assets/locales/ar-SA/wificonfig.ogg b/main/assets/locales/ar-SA/wificonfig.ogg new file mode 100644 index 0000000..b82f7a8 Binary files /dev/null and b/main/assets/locales/ar-SA/wificonfig.ogg differ diff --git a/main/assets/locales/bg-BG/0.ogg b/main/assets/locales/bg-BG/0.ogg new file mode 100644 index 0000000..0cf6483 Binary files /dev/null and b/main/assets/locales/bg-BG/0.ogg differ diff --git a/main/assets/locales/bg-BG/1.ogg b/main/assets/locales/bg-BG/1.ogg new file mode 100644 index 0000000..68bc66b Binary files /dev/null and b/main/assets/locales/bg-BG/1.ogg differ diff --git a/main/assets/locales/bg-BG/2.ogg b/main/assets/locales/bg-BG/2.ogg new file mode 100644 index 0000000..71f874d Binary files /dev/null and b/main/assets/locales/bg-BG/2.ogg differ diff --git a/main/assets/locales/bg-BG/3.ogg b/main/assets/locales/bg-BG/3.ogg new file mode 100644 index 0000000..95aaceb Binary files /dev/null and b/main/assets/locales/bg-BG/3.ogg differ diff --git a/main/assets/locales/bg-BG/4.ogg b/main/assets/locales/bg-BG/4.ogg new file mode 100644 index 0000000..af31cf7 Binary files /dev/null and b/main/assets/locales/bg-BG/4.ogg differ diff --git a/main/assets/locales/bg-BG/5.ogg b/main/assets/locales/bg-BG/5.ogg new file mode 100644 index 0000000..bae3dd8 Binary files /dev/null and b/main/assets/locales/bg-BG/5.ogg differ diff --git a/main/assets/locales/bg-BG/6.ogg b/main/assets/locales/bg-BG/6.ogg new file mode 100644 index 0000000..7271edc Binary files /dev/null and b/main/assets/locales/bg-BG/6.ogg differ diff --git a/main/assets/locales/bg-BG/7.ogg b/main/assets/locales/bg-BG/7.ogg new file mode 100644 index 0000000..707f7f2 Binary files /dev/null and b/main/assets/locales/bg-BG/7.ogg differ diff --git a/main/assets/locales/bg-BG/8.ogg b/main/assets/locales/bg-BG/8.ogg new file mode 100644 index 0000000..52c4513 Binary files /dev/null and b/main/assets/locales/bg-BG/8.ogg differ diff --git a/main/assets/locales/bg-BG/9.ogg b/main/assets/locales/bg-BG/9.ogg new file mode 100644 index 0000000..dd5a37f Binary files /dev/null and b/main/assets/locales/bg-BG/9.ogg differ diff --git a/main/assets/locales/bg-BG/activation.ogg b/main/assets/locales/bg-BG/activation.ogg new file mode 100644 index 0000000..d9bfb78 Binary files /dev/null and b/main/assets/locales/bg-BG/activation.ogg differ diff --git a/main/assets/locales/bg-BG/err_pin.ogg b/main/assets/locales/bg-BG/err_pin.ogg new file mode 100644 index 0000000..5a1f5cc Binary files /dev/null and b/main/assets/locales/bg-BG/err_pin.ogg differ diff --git a/main/assets/locales/bg-BG/err_reg.ogg b/main/assets/locales/bg-BG/err_reg.ogg new file mode 100644 index 0000000..992557c Binary files /dev/null and b/main/assets/locales/bg-BG/err_reg.ogg differ diff --git a/main/assets/locales/bg-BG/language.json b/main/assets/locales/bg-BG/language.json new file mode 100644 index 0000000..9a6b05e --- /dev/null +++ b/main/assets/locales/bg-BG/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "bg-BG" + }, + "strings": { + "WARNING": "Предупреждение", + "INFO": "Информация", + "ERROR": "Грешка", + "VERSION": "Версия ", + "LOADING_PROTOCOL": "Влизане в системата...", + "INITIALIZING": "Инициализация...", + "PIN_ERROR": "Моля, поставете SIM карта", + "REG_ERROR": "Не може да се осъществи достъп до мрежата, моля проверете статуса на SIM картата", + "DETECTING_MODULE": "Откриване на модул...", + "REGISTERING_NETWORK": "Изчакване на мрежата...", + "CHECKING_NEW_VERSION": "Проверка за нова версия...", + "CHECK_NEW_VERSION_FAILED": "Проверката за нова версия е неуспешна, ще се опита отново след %d секунди: %s", + "SWITCH_TO_WIFI_NETWORK": "Превключване към Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Превключване към 4G...", + "STANDBY": "Режим на готовност", + "CONNECT_TO": "Свързване към ", + "CONNECTING": "Свързване...", + "CONNECTION_SUCCESSFUL": "Успешно свързване", + "CONNECTED_TO": "Свързан към ", + "LISTENING": "Слушане...", + "SPEAKING": "Говорене...", + "SERVER_NOT_FOUND": "Търсене на налична услуга", + "SERVER_NOT_CONNECTED": "Не може да се свърже с услугата, моля опитайте по-късно", + "SERVER_TIMEOUT": "Времето за изчакване на отговор изтече", + "SERVER_ERROR": "Неуспешно изпращане, моля проверете мрежата", + "CONNECT_TO_HOTSPOT": "Горещa точка: ", + "ACCESS_VIA_BROWSER": " Конфигурационен URL: ", + "WIFI_CONFIG_MODE": "Режим на конфигуриране на Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Влизане в режим на конфигуриране на Wi-Fi...", + "SCANNING_WIFI": "Сканиране на Wi-Fi...", + "NEW_VERSION": "Нова версия ", + "OTA_UPGRADE": "OTA надстройка", + "UPGRADING": "Системата се надстройва...", + "UPGRADE_FAILED": "Надстройката е неуспешна", + "ACTIVATION": "Активация", + "BATTERY_LOW": "Слаба батерия", + "BATTERY_CHARGING": "Зарядна", + "BATTERY_FULL": "Батерията е пълна", + "BATTERY_NEED_CHARGE": "Слаба батерия, моля заредете", + "VOLUME": "Сила на звука ", + "MUTED": "Заглушено", + "MAX_VOLUME": "Максимална сила на звука", + "RTC_MODE_OFF": "AEC изключен", + "RTC_MODE_ON": "AEC включен", + "PLEASE_WAIT": "Моля, изчакайте...", + "FOUND_NEW_ASSETS": "Намерени нови ресурси: %s", + "DOWNLOAD_ASSETS_FAILED": "Неуспешно изтегляне на ресурси", + "LOADING_ASSETS": "Зареждане на ресурси...", + "HELLO_MY_FRIEND": "Здравей, мой приятел!" + } +} + diff --git a/main/assets/locales/bg-BG/upgrade.ogg b/main/assets/locales/bg-BG/upgrade.ogg new file mode 100644 index 0000000..9c1a885 Binary files /dev/null and b/main/assets/locales/bg-BG/upgrade.ogg differ diff --git a/main/assets/locales/bg-BG/welcome.ogg b/main/assets/locales/bg-BG/welcome.ogg new file mode 100644 index 0000000..71e547b Binary files /dev/null and b/main/assets/locales/bg-BG/welcome.ogg differ diff --git a/main/assets/locales/bg-BG/wificonfig.ogg b/main/assets/locales/bg-BG/wificonfig.ogg new file mode 100644 index 0000000..7d84033 Binary files /dev/null and b/main/assets/locales/bg-BG/wificonfig.ogg differ diff --git a/main/assets/locales/ca-ES/0.ogg b/main/assets/locales/ca-ES/0.ogg new file mode 100644 index 0000000..2934044 Binary files /dev/null and b/main/assets/locales/ca-ES/0.ogg differ diff --git a/main/assets/locales/ca-ES/1.ogg b/main/assets/locales/ca-ES/1.ogg new file mode 100644 index 0000000..2069b40 Binary files /dev/null and b/main/assets/locales/ca-ES/1.ogg differ diff --git a/main/assets/locales/ca-ES/2.ogg b/main/assets/locales/ca-ES/2.ogg new file mode 100644 index 0000000..926011c Binary files /dev/null and b/main/assets/locales/ca-ES/2.ogg differ diff --git a/main/assets/locales/ca-ES/3.ogg b/main/assets/locales/ca-ES/3.ogg new file mode 100644 index 0000000..ce93833 Binary files /dev/null and b/main/assets/locales/ca-ES/3.ogg differ diff --git a/main/assets/locales/ca-ES/4.ogg b/main/assets/locales/ca-ES/4.ogg new file mode 100644 index 0000000..8a3b4a9 Binary files /dev/null and b/main/assets/locales/ca-ES/4.ogg differ diff --git a/main/assets/locales/ca-ES/5.ogg b/main/assets/locales/ca-ES/5.ogg new file mode 100644 index 0000000..87144f5 Binary files /dev/null and b/main/assets/locales/ca-ES/5.ogg differ diff --git a/main/assets/locales/ca-ES/6.ogg b/main/assets/locales/ca-ES/6.ogg new file mode 100644 index 0000000..b640829 Binary files /dev/null and b/main/assets/locales/ca-ES/6.ogg differ diff --git a/main/assets/locales/ca-ES/7.ogg b/main/assets/locales/ca-ES/7.ogg new file mode 100644 index 0000000..f6039c5 Binary files /dev/null and b/main/assets/locales/ca-ES/7.ogg differ diff --git a/main/assets/locales/ca-ES/8.ogg b/main/assets/locales/ca-ES/8.ogg new file mode 100644 index 0000000..c6cca34 Binary files /dev/null and b/main/assets/locales/ca-ES/8.ogg differ diff --git a/main/assets/locales/ca-ES/9.ogg b/main/assets/locales/ca-ES/9.ogg new file mode 100644 index 0000000..704dca0 Binary files /dev/null and b/main/assets/locales/ca-ES/9.ogg differ diff --git a/main/assets/locales/ca-ES/activation.ogg b/main/assets/locales/ca-ES/activation.ogg new file mode 100644 index 0000000..082e561 Binary files /dev/null and b/main/assets/locales/ca-ES/activation.ogg differ diff --git a/main/assets/locales/ca-ES/err_pin.ogg b/main/assets/locales/ca-ES/err_pin.ogg new file mode 100644 index 0000000..ea11662 Binary files /dev/null and b/main/assets/locales/ca-ES/err_pin.ogg differ diff --git a/main/assets/locales/ca-ES/err_reg.ogg b/main/assets/locales/ca-ES/err_reg.ogg new file mode 100644 index 0000000..3e9b042 Binary files /dev/null and b/main/assets/locales/ca-ES/err_reg.ogg differ diff --git a/main/assets/locales/ca-ES/language.json b/main/assets/locales/ca-ES/language.json new file mode 100644 index 0000000..02337e3 --- /dev/null +++ b/main/assets/locales/ca-ES/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "ca-ES" + }, + "strings": { + "WARNING": "Advertència", + "INFO": "Informació", + "ERROR": "Error", + "VERSION": "Versió ", + "LOADING_PROTOCOL": "Iniciant sessió...", + "INITIALIZING": "Inicialitzant...", + "PIN_ERROR": "Si us plau, inseriu la targeta SIM", + "REG_ERROR": "No es pot accedir a la xarxa, si us plau comproveu l'estat de la targeta SIM", + "DETECTING_MODULE": "Detectant mòdul...", + "REGISTERING_NETWORK": "Esperant la xarxa...", + "CHECKING_NEW_VERSION": "Comprovant nova versió...", + "CHECK_NEW_VERSION_FAILED": "La comprovació de nova versió ha fallat, es tornarà a intentar en %d segons: %s", + "SWITCH_TO_WIFI_NETWORK": "Canviant a Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Canviant a 4G...", + "STANDBY": "En espera", + "CONNECT_TO": "Connectar a ", + "CONNECTING": "Connectant...", + "CONNECTION_SUCCESSFUL": "Connexió exitosa", + "CONNECTED_TO": "Connectat a ", + "LISTENING": "Escoltant...", + "SPEAKING": "Parlant...", + "SERVER_NOT_FOUND": "Buscant servei disponible", + "SERVER_NOT_CONNECTED": "No es pot connectar al servei, si us plau intenteu-ho més tard", + "SERVER_TIMEOUT": "Temps d'espera de resposta exhaurit", + "SERVER_ERROR": "L'enviament ha fallat, si us plau comproveu la xarxa", + "CONNECT_TO_HOTSPOT": "Punt d'accés: ", + "ACCESS_VIA_BROWSER": " URL de configuració: ", + "WIFI_CONFIG_MODE": "Mode de configuració Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Entrant en mode de configuració Wi-Fi...", + "SCANNING_WIFI": "Escanejant Wi-Fi...", + "NEW_VERSION": "Nova versió ", + "OTA_UPGRADE": "Actualització OTA", + "UPGRADING": "El sistema s'està actualitzant...", + "UPGRADE_FAILED": "L'actualització ha fallat", + "ACTIVATION": "Activació", + "BATTERY_LOW": "Bateria baixa", + "BATTERY_CHARGING": "Carregant", + "BATTERY_FULL": "Bateria plena", + "BATTERY_NEED_CHARGE": "Bateria baixa, si us plau carregueu", + "VOLUME": "Volum ", + "MUTED": "Silenciat", + "MAX_VOLUME": "Volum màxim", + "RTC_MODE_OFF": "AEC desactivat", + "RTC_MODE_ON": "AEC activat", + "PLEASE_WAIT": "Si us plau, espereu...", + "FOUND_NEW_ASSETS": "S'han trobat nous recursos: %s", + "DOWNLOAD_ASSETS_FAILED": "No s'han pogut descarregar els recursos", + "LOADING_ASSETS": "Carregant recursos...", + "HELLO_MY_FRIEND": "Hola, amic meu!" + } +} + diff --git a/main/assets/locales/ca-ES/upgrade.ogg b/main/assets/locales/ca-ES/upgrade.ogg new file mode 100644 index 0000000..1bb2f28 Binary files /dev/null and b/main/assets/locales/ca-ES/upgrade.ogg differ diff --git a/main/assets/locales/ca-ES/welcome.ogg b/main/assets/locales/ca-ES/welcome.ogg new file mode 100644 index 0000000..530d04e Binary files /dev/null and b/main/assets/locales/ca-ES/welcome.ogg differ diff --git a/main/assets/locales/ca-ES/wificonfig.ogg b/main/assets/locales/ca-ES/wificonfig.ogg new file mode 100644 index 0000000..a4b77cd Binary files /dev/null and b/main/assets/locales/ca-ES/wificonfig.ogg differ diff --git a/main/assets/locales/cs-CZ/0.ogg b/main/assets/locales/cs-CZ/0.ogg new file mode 100644 index 0000000..96891e6 Binary files /dev/null and b/main/assets/locales/cs-CZ/0.ogg differ diff --git a/main/assets/locales/cs-CZ/1.ogg b/main/assets/locales/cs-CZ/1.ogg new file mode 100644 index 0000000..a12d638 Binary files /dev/null and b/main/assets/locales/cs-CZ/1.ogg differ diff --git a/main/assets/locales/cs-CZ/2.ogg b/main/assets/locales/cs-CZ/2.ogg new file mode 100644 index 0000000..a18d97e Binary files /dev/null and b/main/assets/locales/cs-CZ/2.ogg differ diff --git a/main/assets/locales/cs-CZ/3.ogg b/main/assets/locales/cs-CZ/3.ogg new file mode 100644 index 0000000..a2d9d3d Binary files /dev/null and b/main/assets/locales/cs-CZ/3.ogg differ diff --git a/main/assets/locales/cs-CZ/4.ogg b/main/assets/locales/cs-CZ/4.ogg new file mode 100644 index 0000000..76646ed Binary files /dev/null and b/main/assets/locales/cs-CZ/4.ogg differ diff --git a/main/assets/locales/cs-CZ/5.ogg b/main/assets/locales/cs-CZ/5.ogg new file mode 100644 index 0000000..2d9ab25 Binary files /dev/null and b/main/assets/locales/cs-CZ/5.ogg differ diff --git a/main/assets/locales/cs-CZ/6.ogg b/main/assets/locales/cs-CZ/6.ogg new file mode 100644 index 0000000..571ff30 Binary files /dev/null and b/main/assets/locales/cs-CZ/6.ogg differ diff --git a/main/assets/locales/cs-CZ/7.ogg b/main/assets/locales/cs-CZ/7.ogg new file mode 100644 index 0000000..e8f0f94 Binary files /dev/null and b/main/assets/locales/cs-CZ/7.ogg differ diff --git a/main/assets/locales/cs-CZ/8.ogg b/main/assets/locales/cs-CZ/8.ogg new file mode 100644 index 0000000..0f72a58 Binary files /dev/null and b/main/assets/locales/cs-CZ/8.ogg differ diff --git a/main/assets/locales/cs-CZ/9.ogg b/main/assets/locales/cs-CZ/9.ogg new file mode 100644 index 0000000..c102667 Binary files /dev/null and b/main/assets/locales/cs-CZ/9.ogg differ diff --git a/main/assets/locales/cs-CZ/activation.ogg b/main/assets/locales/cs-CZ/activation.ogg new file mode 100644 index 0000000..b4334a4 Binary files /dev/null and b/main/assets/locales/cs-CZ/activation.ogg differ diff --git a/main/assets/locales/cs-CZ/err_pin.ogg b/main/assets/locales/cs-CZ/err_pin.ogg new file mode 100644 index 0000000..07818a1 Binary files /dev/null and b/main/assets/locales/cs-CZ/err_pin.ogg differ diff --git a/main/assets/locales/cs-CZ/err_reg.ogg b/main/assets/locales/cs-CZ/err_reg.ogg new file mode 100644 index 0000000..6d4752e Binary files /dev/null and b/main/assets/locales/cs-CZ/err_reg.ogg differ diff --git a/main/assets/locales/cs-CZ/language.json b/main/assets/locales/cs-CZ/language.json new file mode 100644 index 0000000..1e18a5c --- /dev/null +++ b/main/assets/locales/cs-CZ/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "cs-CZ" + }, + "strings": { + "WARNING": "Varování", + "INFO": "Informace", + "ERROR": "Chyba", + "VERSION": "Verze ", + "LOADING_PROTOCOL": "Připojování k serveru...", + "INITIALIZING": "Inicializace...", + "PIN_ERROR": "Prosím vložte SIM kartu", + "REG_ERROR": "Nelze se připojit k síti, zkontrolujte stav datové karty", + "DETECTING_MODULE": "Detekce modulu...", + "REGISTERING_NETWORK": "Čekání na síť...", + "CHECKING_NEW_VERSION": "Kontrola nové verze...", + "CHECK_NEW_VERSION_FAILED": "Kontrola nové verze selhala, opakování za %d sekund: %s", + "SWITCH_TO_WIFI_NETWORK": "Přepínání na Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Přepínání na 4G...", + "STANDBY": "Pohotovost", + "CONNECT_TO": "Připojit k ", + "CONNECTING": "Připojování...", + "CONNECTED_TO": "Připojeno k ", + "LISTENING": "Naslouchání...", + "SPEAKING": "Mluvení...", + "SERVER_NOT_FOUND": "Hledání dostupné služby", + "SERVER_NOT_CONNECTED": "Nelze se připojit ke službě, zkuste to později", + "SERVER_TIMEOUT": "Čas odpovědi vypršel", + "SERVER_ERROR": "Odeslání selhalo, zkontrolujte síť", + "CONNECT_TO_HOTSPOT": "Připojte telefon k hotspotu ", + "ACCESS_VIA_BROWSER": ",přístup přes prohlížeč ", + "WIFI_CONFIG_MODE": "Režim konfigurace sítě", + "ENTERING_WIFI_CONFIG_MODE": "Vstup do režimu konfigurace sítě...", + "SCANNING_WIFI": "Skenování Wi-Fi...", + "NEW_VERSION": "Nová verze ", + "OTA_UPGRADE": "OTA upgrade", + "UPGRADING": "Aktualizace systému...", + "UPGRADE_FAILED": "Upgrade selhal", + "ACTIVATION": "Aktivace zařízení", + "BATTERY_LOW": "Slabá baterie", + "BATTERY_CHARGING": "Nabíjení", + "BATTERY_FULL": "Baterie plná", + "BATTERY_NEED_CHARGE": "Slabá baterie, prosím nabijte", + "VOLUME": "Hlasitost ", + "MUTED": "Ztlumeno", + "MAX_VOLUME": "Maximální hlasitost", + "RTC_MODE_OFF": "AEC vypnuto", + "RTC_MODE_ON": "AEC zapnuto", + "DOWNLOAD_ASSETS_FAILED": "Nepodařilo se stáhnout prostředky", + "LOADING_ASSETS": "Načítání prostředků...", + "PLEASE_WAIT": "Prosím čekejte...", + "FOUND_NEW_ASSETS": "Nalezeny nové prostředky: %s", + "HELLO_MY_FRIEND": "Ahoj, můj příteli!" + } +} \ No newline at end of file diff --git a/main/assets/locales/cs-CZ/upgrade.ogg b/main/assets/locales/cs-CZ/upgrade.ogg new file mode 100644 index 0000000..e29edc5 Binary files /dev/null and b/main/assets/locales/cs-CZ/upgrade.ogg differ diff --git a/main/assets/locales/cs-CZ/welcome.ogg b/main/assets/locales/cs-CZ/welcome.ogg new file mode 100644 index 0000000..7a0625e Binary files /dev/null and b/main/assets/locales/cs-CZ/welcome.ogg differ diff --git a/main/assets/locales/cs-CZ/wificonfig.ogg b/main/assets/locales/cs-CZ/wificonfig.ogg new file mode 100644 index 0000000..bc945a9 Binary files /dev/null and b/main/assets/locales/cs-CZ/wificonfig.ogg differ diff --git a/main/assets/locales/da-DK/0.ogg b/main/assets/locales/da-DK/0.ogg new file mode 100644 index 0000000..b27207c Binary files /dev/null and b/main/assets/locales/da-DK/0.ogg differ diff --git a/main/assets/locales/da-DK/1.ogg b/main/assets/locales/da-DK/1.ogg new file mode 100644 index 0000000..5fd2fce Binary files /dev/null and b/main/assets/locales/da-DK/1.ogg differ diff --git a/main/assets/locales/da-DK/2.ogg b/main/assets/locales/da-DK/2.ogg new file mode 100644 index 0000000..f3be2ac Binary files /dev/null and b/main/assets/locales/da-DK/2.ogg differ diff --git a/main/assets/locales/da-DK/3.ogg b/main/assets/locales/da-DK/3.ogg new file mode 100644 index 0000000..3ad6f10 Binary files /dev/null and b/main/assets/locales/da-DK/3.ogg differ diff --git a/main/assets/locales/da-DK/4.ogg b/main/assets/locales/da-DK/4.ogg new file mode 100644 index 0000000..8684e63 Binary files /dev/null and b/main/assets/locales/da-DK/4.ogg differ diff --git a/main/assets/locales/da-DK/5.ogg b/main/assets/locales/da-DK/5.ogg new file mode 100644 index 0000000..29559fd Binary files /dev/null and b/main/assets/locales/da-DK/5.ogg differ diff --git a/main/assets/locales/da-DK/6.ogg b/main/assets/locales/da-DK/6.ogg new file mode 100644 index 0000000..d0b9ad7 Binary files /dev/null and b/main/assets/locales/da-DK/6.ogg differ diff --git a/main/assets/locales/da-DK/7.ogg b/main/assets/locales/da-DK/7.ogg new file mode 100644 index 0000000..28ecaca Binary files /dev/null and b/main/assets/locales/da-DK/7.ogg differ diff --git a/main/assets/locales/da-DK/8.ogg b/main/assets/locales/da-DK/8.ogg new file mode 100644 index 0000000..2d71851 Binary files /dev/null and b/main/assets/locales/da-DK/8.ogg differ diff --git a/main/assets/locales/da-DK/9.ogg b/main/assets/locales/da-DK/9.ogg new file mode 100644 index 0000000..11af485 Binary files /dev/null and b/main/assets/locales/da-DK/9.ogg differ diff --git a/main/assets/locales/da-DK/activation.ogg b/main/assets/locales/da-DK/activation.ogg new file mode 100644 index 0000000..58b9b43 Binary files /dev/null and b/main/assets/locales/da-DK/activation.ogg differ diff --git a/main/assets/locales/da-DK/err_pin.ogg b/main/assets/locales/da-DK/err_pin.ogg new file mode 100644 index 0000000..391d984 Binary files /dev/null and b/main/assets/locales/da-DK/err_pin.ogg differ diff --git a/main/assets/locales/da-DK/err_reg.ogg b/main/assets/locales/da-DK/err_reg.ogg new file mode 100644 index 0000000..199f807 Binary files /dev/null and b/main/assets/locales/da-DK/err_reg.ogg differ diff --git a/main/assets/locales/da-DK/language.json b/main/assets/locales/da-DK/language.json new file mode 100644 index 0000000..918598b --- /dev/null +++ b/main/assets/locales/da-DK/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "da-DK" + }, + "strings": { + "WARNING": "Advarsel", + "INFO": "Information", + "ERROR": "Fejl", + "VERSION": "Version ", + "LOADING_PROTOCOL": "Logger ind...", + "INITIALIZING": "Initialiserer...", + "PIN_ERROR": "Indsæt venligst SIM-kort", + "REG_ERROR": "Kan ikke få adgang til netværket, tjek venligst SIM-kortets status", + "DETECTING_MODULE": "Detekterer modul...", + "REGISTERING_NETWORK": "Venter på netværk...", + "CHECKING_NEW_VERSION": "Tjekker for ny version...", + "CHECK_NEW_VERSION_FAILED": "Tjek for ny version mislykkedes, prøver igen om %d sekunder: %s", + "SWITCH_TO_WIFI_NETWORK": "Skifter til Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Skifter til 4G...", + "STANDBY": "Standby", + "CONNECT_TO": "Forbind til ", + "CONNECTING": "Forbinder...", + "CONNECTION_SUCCESSFUL": "Forbindelse lykkedes", + "CONNECTED_TO": "Forbundet til ", + "LISTENING": "Lytter...", + "SPEAKING": "Taler...", + "SERVER_NOT_FOUND": "Søger efter tilgængelig tjeneste", + "SERVER_NOT_CONNECTED": "Kan ikke forbinde til tjeneste, prøv venligst igen senere", + "SERVER_TIMEOUT": "Timeout ved venten på svar", + "SERVER_ERROR": "Afsendelse mislykkedes, tjek venligst netværket", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Konfigurations-URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi-konfigurationstilstand", + "ENTERING_WIFI_CONFIG_MODE": "Går ind i Wi-Fi-konfigurationstilstand...", + "SCANNING_WIFI": "Scanner Wi-Fi...", + "NEW_VERSION": "Ny version ", + "OTA_UPGRADE": "OTA-opgradering", + "UPGRADING": "Systemet opgraderes...", + "UPGRADE_FAILED": "Opgradering mislykkedes", + "ACTIVATION": "Aktivering", + "BATTERY_LOW": "Lavt batteri", + "BATTERY_CHARGING": "Oplader", + "BATTERY_FULL": "Batteriet er fuldt", + "BATTERY_NEED_CHARGE": "Lavt batteri, oplad venligst", + "VOLUME": "Lydstyrke ", + "MUTED": "Lydløs", + "MAX_VOLUME": "Maksimal lydstyrke", + "RTC_MODE_OFF": "AEC slukket", + "RTC_MODE_ON": "AEC tændt", + "PLEASE_WAIT": "Vent venligst...", + "FOUND_NEW_ASSETS": "Fandt nye ressourcer: %s", + "DOWNLOAD_ASSETS_FAILED": "Download af ressourcer mislykkedes", + "LOADING_ASSETS": "Indlæser ressourcer...", + "HELLO_MY_FRIEND": "Hej, min ven!" + } +} + diff --git a/main/assets/locales/da-DK/upgrade.ogg b/main/assets/locales/da-DK/upgrade.ogg new file mode 100644 index 0000000..b3e1c29 Binary files /dev/null and b/main/assets/locales/da-DK/upgrade.ogg differ diff --git a/main/assets/locales/da-DK/welcome.ogg b/main/assets/locales/da-DK/welcome.ogg new file mode 100644 index 0000000..f211cc4 Binary files /dev/null and b/main/assets/locales/da-DK/welcome.ogg differ diff --git a/main/assets/locales/da-DK/wificonfig.ogg b/main/assets/locales/da-DK/wificonfig.ogg new file mode 100644 index 0000000..33ea9c5 Binary files /dev/null and b/main/assets/locales/da-DK/wificonfig.ogg differ diff --git a/main/assets/locales/de-DE/0.ogg b/main/assets/locales/de-DE/0.ogg new file mode 100644 index 0000000..a3cdb23 Binary files /dev/null and b/main/assets/locales/de-DE/0.ogg differ diff --git a/main/assets/locales/de-DE/1.ogg b/main/assets/locales/de-DE/1.ogg new file mode 100644 index 0000000..fb4fd93 Binary files /dev/null and b/main/assets/locales/de-DE/1.ogg differ diff --git a/main/assets/locales/de-DE/2.ogg b/main/assets/locales/de-DE/2.ogg new file mode 100644 index 0000000..fb09b60 Binary files /dev/null and b/main/assets/locales/de-DE/2.ogg differ diff --git a/main/assets/locales/de-DE/3.ogg b/main/assets/locales/de-DE/3.ogg new file mode 100644 index 0000000..d3f7549 Binary files /dev/null and b/main/assets/locales/de-DE/3.ogg differ diff --git a/main/assets/locales/de-DE/4.ogg b/main/assets/locales/de-DE/4.ogg new file mode 100644 index 0000000..46db0ce Binary files /dev/null and b/main/assets/locales/de-DE/4.ogg differ diff --git a/main/assets/locales/de-DE/5.ogg b/main/assets/locales/de-DE/5.ogg new file mode 100644 index 0000000..3ceee0f Binary files /dev/null and b/main/assets/locales/de-DE/5.ogg differ diff --git a/main/assets/locales/de-DE/6.ogg b/main/assets/locales/de-DE/6.ogg new file mode 100644 index 0000000..8942550 Binary files /dev/null and b/main/assets/locales/de-DE/6.ogg differ diff --git a/main/assets/locales/de-DE/7.ogg b/main/assets/locales/de-DE/7.ogg new file mode 100644 index 0000000..3b6957d Binary files /dev/null and b/main/assets/locales/de-DE/7.ogg differ diff --git a/main/assets/locales/de-DE/8.ogg b/main/assets/locales/de-DE/8.ogg new file mode 100644 index 0000000..421f018 Binary files /dev/null and b/main/assets/locales/de-DE/8.ogg differ diff --git a/main/assets/locales/de-DE/9.ogg b/main/assets/locales/de-DE/9.ogg new file mode 100644 index 0000000..40b7876 Binary files /dev/null and b/main/assets/locales/de-DE/9.ogg differ diff --git a/main/assets/locales/de-DE/activation.ogg b/main/assets/locales/de-DE/activation.ogg new file mode 100644 index 0000000..3dfccbd Binary files /dev/null and b/main/assets/locales/de-DE/activation.ogg differ diff --git a/main/assets/locales/de-DE/err_pin.ogg b/main/assets/locales/de-DE/err_pin.ogg new file mode 100644 index 0000000..8d2eef9 Binary files /dev/null and b/main/assets/locales/de-DE/err_pin.ogg differ diff --git a/main/assets/locales/de-DE/err_reg.ogg b/main/assets/locales/de-DE/err_reg.ogg new file mode 100644 index 0000000..430b876 Binary files /dev/null and b/main/assets/locales/de-DE/err_reg.ogg differ diff --git a/main/assets/locales/de-DE/language.json b/main/assets/locales/de-DE/language.json new file mode 100644 index 0000000..724e267 --- /dev/null +++ b/main/assets/locales/de-DE/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "de-DE" + }, + "strings": { + "WARNING": "Warnung", + "INFO": "Information", + "ERROR": "Fehler", + "VERSION": "Version ", + "LOADING_PROTOCOL": "Verbindung zum Server...", + "INITIALIZING": "Initialisierung...", + "PIN_ERROR": "Bitte SIM-Karte einlegen", + "REG_ERROR": "Netzwerkverbindung fehlgeschlagen, bitte Datenkartenstatus prüfen", + "DETECTING_MODULE": "Modul erkennen...", + "REGISTERING_NETWORK": "Auf Netzwerk warten...", + "CHECKING_NEW_VERSION": "Neue Version prüfen...", + "CHECK_NEW_VERSION_FAILED": "Neue Version prüfen fehlgeschlagen, Wiederholung in %d Sekunden: %s", + "SWITCH_TO_WIFI_NETWORK": "Zu Wi-Fi wechseln...", + "SWITCH_TO_4G_NETWORK": "Zu 4G wechseln...", + "STANDBY": "Bereitschaft", + "CONNECT_TO": "Verbinden zu ", + "CONNECTING": "Verbindung wird hergestellt...", + "CONNECTED_TO": "Verbunden mit ", + "LISTENING": "Zuhören...", + "SPEAKING": "Sprechen...", + "SERVER_NOT_FOUND": "Verfügbaren Service suchen", + "SERVER_NOT_CONNECTED": "Service-Verbindung fehlgeschlagen, bitte später versuchen", + "SERVER_TIMEOUT": "Antwort-Timeout", + "SERVER_ERROR": "Senden fehlgeschlagen, bitte Netzwerk prüfen", + "CONNECT_TO_HOTSPOT": "Handy mit Hotspot verbinden ", + "ACCESS_VIA_BROWSER": ",Browser öffnen ", + "WIFI_CONFIG_MODE": "Netzwerkkonfigurationsmodus", + "ENTERING_WIFI_CONFIG_MODE": "Netzwerkkonfigurationsmodus eingeben...", + "SCANNING_WIFI": "Wi-Fi scannen...", + "NEW_VERSION": "Neue Version ", + "OTA_UPGRADE": "OTA-Upgrade", + "UPGRADING": "System wird aktualisiert...", + "UPGRADE_FAILED": "Upgrade fehlgeschlagen", + "ACTIVATION": "Gerät aktivieren", + "BATTERY_LOW": "Niedriger Batteriestand", + "BATTERY_CHARGING": "Wird geladen", + "BATTERY_FULL": "Batterie voll", + "BATTERY_NEED_CHARGE": "Niedriger Batteriestand, bitte aufladen", + "VOLUME": "Lautstärke ", + "MUTED": "Stummgeschaltet", + "MAX_VOLUME": "Maximale Lautstärke", + "RTC_MODE_OFF": "AEC aus", + "RTC_MODE_ON": "AEC ein", + "DOWNLOAD_ASSETS_FAILED": "Fehler beim Herunterladen der Ressourcen", + "LOADING_ASSETS": "Ressourcen werden geladen...", + "PLEASE_WAIT": "Bitte warten...", + "FOUND_NEW_ASSETS": "Neue Ressourcen gefunden: %s", + "HELLO_MY_FRIEND": "Hallo, mein Freund!" + } +} \ No newline at end of file diff --git a/main/assets/locales/de-DE/upgrade.ogg b/main/assets/locales/de-DE/upgrade.ogg new file mode 100644 index 0000000..716d7cb Binary files /dev/null and b/main/assets/locales/de-DE/upgrade.ogg differ diff --git a/main/assets/locales/de-DE/welcome.ogg b/main/assets/locales/de-DE/welcome.ogg new file mode 100644 index 0000000..69271ce Binary files /dev/null and b/main/assets/locales/de-DE/welcome.ogg differ diff --git a/main/assets/locales/de-DE/wificonfig.ogg b/main/assets/locales/de-DE/wificonfig.ogg new file mode 100644 index 0000000..a3d753d Binary files /dev/null and b/main/assets/locales/de-DE/wificonfig.ogg differ diff --git a/main/assets/locales/el-GR/0.ogg b/main/assets/locales/el-GR/0.ogg new file mode 100644 index 0000000..b06bdb5 Binary files /dev/null and b/main/assets/locales/el-GR/0.ogg differ diff --git a/main/assets/locales/el-GR/1.ogg b/main/assets/locales/el-GR/1.ogg new file mode 100644 index 0000000..4a9b7d2 Binary files /dev/null and b/main/assets/locales/el-GR/1.ogg differ diff --git a/main/assets/locales/el-GR/2.ogg b/main/assets/locales/el-GR/2.ogg new file mode 100644 index 0000000..eeb149d Binary files /dev/null and b/main/assets/locales/el-GR/2.ogg differ diff --git a/main/assets/locales/el-GR/3.ogg b/main/assets/locales/el-GR/3.ogg new file mode 100644 index 0000000..5364664 Binary files /dev/null and b/main/assets/locales/el-GR/3.ogg differ diff --git a/main/assets/locales/el-GR/4.ogg b/main/assets/locales/el-GR/4.ogg new file mode 100644 index 0000000..cbdf259 Binary files /dev/null and b/main/assets/locales/el-GR/4.ogg differ diff --git a/main/assets/locales/el-GR/5.ogg b/main/assets/locales/el-GR/5.ogg new file mode 100644 index 0000000..1e93b72 Binary files /dev/null and b/main/assets/locales/el-GR/5.ogg differ diff --git a/main/assets/locales/el-GR/6.ogg b/main/assets/locales/el-GR/6.ogg new file mode 100644 index 0000000..a831a42 Binary files /dev/null and b/main/assets/locales/el-GR/6.ogg differ diff --git a/main/assets/locales/el-GR/7.ogg b/main/assets/locales/el-GR/7.ogg new file mode 100644 index 0000000..1c64b31 Binary files /dev/null and b/main/assets/locales/el-GR/7.ogg differ diff --git a/main/assets/locales/el-GR/8.ogg b/main/assets/locales/el-GR/8.ogg new file mode 100644 index 0000000..d7a9696 Binary files /dev/null and b/main/assets/locales/el-GR/8.ogg differ diff --git a/main/assets/locales/el-GR/9.ogg b/main/assets/locales/el-GR/9.ogg new file mode 100644 index 0000000..8ff0b07 Binary files /dev/null and b/main/assets/locales/el-GR/9.ogg differ diff --git a/main/assets/locales/el-GR/activation.ogg b/main/assets/locales/el-GR/activation.ogg new file mode 100644 index 0000000..aa8b401 Binary files /dev/null and b/main/assets/locales/el-GR/activation.ogg differ diff --git a/main/assets/locales/el-GR/err_pin.ogg b/main/assets/locales/el-GR/err_pin.ogg new file mode 100644 index 0000000..7c10086 Binary files /dev/null and b/main/assets/locales/el-GR/err_pin.ogg differ diff --git a/main/assets/locales/el-GR/err_reg.ogg b/main/assets/locales/el-GR/err_reg.ogg new file mode 100644 index 0000000..f65513a Binary files /dev/null and b/main/assets/locales/el-GR/err_reg.ogg differ diff --git a/main/assets/locales/el-GR/language.json b/main/assets/locales/el-GR/language.json new file mode 100644 index 0000000..ccbea53 --- /dev/null +++ b/main/assets/locales/el-GR/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "el-GR" + }, + "strings": { + "WARNING": "Προειδοποίηση", + "INFO": "Πληροφορίες", + "ERROR": "Σφάλμα", + "VERSION": "Έκδοση ", + "LOADING_PROTOCOL": "Σύνδεση...", + "INITIALIZING": "Αρχικοποίηση...", + "PIN_ERROR": "Παρακαλώ εισαγάγετε κάρτα SIM", + "REG_ERROR": "Αδυναμία πρόσβασης στο δίκτυο, ελέγξτε την κατάσταση της κάρτας SIM", + "DETECTING_MODULE": "Ανίχνευση μονάδας...", + "REGISTERING_NETWORK": "Αναμονή δικτύου...", + "CHECKING_NEW_VERSION": "Έλεγχος για νέα έκδοση...", + "CHECK_NEW_VERSION_FAILED": "Ο έλεγχος για νέα έκδοση απέτυχε, θα επαναληφθεί σε %d δευτερόλεπτα: %s", + "SWITCH_TO_WIFI_NETWORK": "Μετάβαση σε Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Μετάβαση σε 4G...", + "STANDBY": "Αναμονή", + "CONNECT_TO": "Σύνδεση σε ", + "CONNECTING": "Σύνδεση...", + "CONNECTION_SUCCESSFUL": "Επιτυχής σύνδεση", + "CONNECTED_TO": "Συνδέθηκε σε ", + "LISTENING": "Ακρόαση...", + "SPEAKING": "Ομιλία...", + "SERVER_NOT_FOUND": "Αναζήτηση διαθέσιμης υπηρεσίας", + "SERVER_NOT_CONNECTED": "Αδυναμία σύνδεσης στην υπηρεσία, παρακαλώ δοκιμάστε αργότερα", + "SERVER_TIMEOUT": "Λήξη χρόνου αναμονής απόκρισης", + "SERVER_ERROR": "Η αποστολή απέτυχε, ελέγξτε το δίκτυο", + "CONNECT_TO_HOTSPOT": "Σημείο πρόσβασης: ", + "ACCESS_VIA_BROWSER": " URL διαμόρφωσης: ", + "WIFI_CONFIG_MODE": "Λειτουργία διαμόρφωσης Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Είσοδος σε λειτουργία διαμόρφωσης Wi-Fi...", + "SCANNING_WIFI": "Σάρωση Wi-Fi...", + "NEW_VERSION": "Νέα έκδοση ", + "OTA_UPGRADE": "Αναβάθμιση OTA", + "UPGRADING": "Το σύστημα αναβαθμίζεται...", + "UPGRADE_FAILED": "Η αναβάθμιση απέτυχε", + "ACTIVATION": "Ενεργοποίηση", + "BATTERY_LOW": "Χαμηλή μπαταρία", + "BATTERY_CHARGING": "Φόρτιση", + "BATTERY_FULL": "Πλήρης μπαταρία", + "BATTERY_NEED_CHARGE": "Χαμηλή μπαταρία, παρακαλώ φορτίστε", + "VOLUME": "Ένταση ", + "MUTED": "Σίγαση", + "MAX_VOLUME": "Μέγιστη ένταση", + "RTC_MODE_OFF": "AEC απενεργοποιημένο", + "RTC_MODE_ON": "AEC ενεργοποιημένο", + "PLEASE_WAIT": "Παρακαλώ περιμένετε...", + "FOUND_NEW_ASSETS": "Βρέθηκαν νέοι πόροι: %s", + "DOWNLOAD_ASSETS_FAILED": "Αποτυχία λήψης πόρων", + "LOADING_ASSETS": "Φόρτωση πόρων...", + "HELLO_MY_FRIEND": "Γεια σου, φίλε μου!" + } +} + diff --git a/main/assets/locales/el-GR/upgrade.ogg b/main/assets/locales/el-GR/upgrade.ogg new file mode 100644 index 0000000..81bef14 Binary files /dev/null and b/main/assets/locales/el-GR/upgrade.ogg differ diff --git a/main/assets/locales/el-GR/welcome.ogg b/main/assets/locales/el-GR/welcome.ogg new file mode 100644 index 0000000..c7a2c7c Binary files /dev/null and b/main/assets/locales/el-GR/welcome.ogg differ diff --git a/main/assets/locales/el-GR/wificonfig.ogg b/main/assets/locales/el-GR/wificonfig.ogg new file mode 100644 index 0000000..fe3eb66 Binary files /dev/null and b/main/assets/locales/el-GR/wificonfig.ogg differ diff --git a/main/assets/locales/en-US/0.ogg b/main/assets/locales/en-US/0.ogg new file mode 100644 index 0000000..51dff41 Binary files /dev/null and b/main/assets/locales/en-US/0.ogg differ diff --git a/main/assets/locales/en-US/1.ogg b/main/assets/locales/en-US/1.ogg new file mode 100644 index 0000000..814753e Binary files /dev/null and b/main/assets/locales/en-US/1.ogg differ diff --git a/main/assets/locales/en-US/2.ogg b/main/assets/locales/en-US/2.ogg new file mode 100644 index 0000000..420a994 Binary files /dev/null and b/main/assets/locales/en-US/2.ogg differ diff --git a/main/assets/locales/en-US/3.ogg b/main/assets/locales/en-US/3.ogg new file mode 100644 index 0000000..1d3fa8a Binary files /dev/null and b/main/assets/locales/en-US/3.ogg differ diff --git a/main/assets/locales/en-US/4.ogg b/main/assets/locales/en-US/4.ogg new file mode 100644 index 0000000..8e364ad Binary files /dev/null and b/main/assets/locales/en-US/4.ogg differ diff --git a/main/assets/locales/en-US/5.ogg b/main/assets/locales/en-US/5.ogg new file mode 100644 index 0000000..5be437d Binary files /dev/null and b/main/assets/locales/en-US/5.ogg differ diff --git a/main/assets/locales/en-US/6.ogg b/main/assets/locales/en-US/6.ogg new file mode 100644 index 0000000..e398409 Binary files /dev/null and b/main/assets/locales/en-US/6.ogg differ diff --git a/main/assets/locales/en-US/7.ogg b/main/assets/locales/en-US/7.ogg new file mode 100644 index 0000000..879aebd Binary files /dev/null and b/main/assets/locales/en-US/7.ogg differ diff --git a/main/assets/locales/en-US/8.ogg b/main/assets/locales/en-US/8.ogg new file mode 100644 index 0000000..0e9efd2 Binary files /dev/null and b/main/assets/locales/en-US/8.ogg differ diff --git a/main/assets/locales/en-US/9.ogg b/main/assets/locales/en-US/9.ogg new file mode 100644 index 0000000..434c320 Binary files /dev/null and b/main/assets/locales/en-US/9.ogg differ diff --git a/main/assets/locales/en-US/activation.ogg b/main/assets/locales/en-US/activation.ogg new file mode 100644 index 0000000..0e9b843 Binary files /dev/null and b/main/assets/locales/en-US/activation.ogg differ diff --git a/main/assets/locales/en-US/err_pin.ogg b/main/assets/locales/en-US/err_pin.ogg new file mode 100644 index 0000000..c52fdf4 Binary files /dev/null and b/main/assets/locales/en-US/err_pin.ogg differ diff --git a/main/assets/locales/en-US/err_reg.ogg b/main/assets/locales/en-US/err_reg.ogg new file mode 100644 index 0000000..95593f4 Binary files /dev/null and b/main/assets/locales/en-US/err_reg.ogg differ diff --git a/main/assets/locales/en-US/language.json b/main/assets/locales/en-US/language.json new file mode 100644 index 0000000..1758d34 --- /dev/null +++ b/main/assets/locales/en-US/language.json @@ -0,0 +1,56 @@ +{ + "language": { + "type": "en-US" + }, + "strings": { + "WARNING": "Warning", + "INFO": "Information", + "ERROR": "Error", + "VERSION": "Ver ", + "LOADING_PROTOCOL": "Logging in...", + "INITIALIZING": "Initializing...", + "PIN_ERROR": "Please insert SIM card", + "REG_ERROR": "Unable to access network, please check SIM card status", + "DETECTING_MODULE": "Detecting module...", + "REGISTERING_NETWORK": "Waiting for network...", + "CHECKING_NEW_VERSION": "Checking for new version...", + "CHECK_NEW_VERSION_FAILED": "Check for new version failed, will retry in %d seconds: %s", + "SWITCH_TO_WIFI_NETWORK": "Switching to Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Switching to 4G...", + "STANDBY": "Standby", + "CONNECT_TO": "Connect to ", + "CONNECTING": "Connecting...", + "CONNECTION_SUCCESSFUL": "Connection Successful", + "CONNECTED_TO": "Connected to ", + "LISTENING": "Listening...", + "SPEAKING": "Speaking...", + "SERVER_NOT_FOUND": "Looking for available service", + "SERVER_NOT_CONNECTED": "Unable to connect to service, please try again later", + "SERVER_TIMEOUT": "Waiting for response timeout", + "SERVER_ERROR": "Sending failed, please check the network", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Config URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi Configuration Mode", + "ENTERING_WIFI_CONFIG_MODE": "Entering Wi-Fi configuration mode...", + "SCANNING_WIFI": "Scanning Wi-Fi...", + "NEW_VERSION": "New version ", + "OTA_UPGRADE": "OTA Upgrade", + "UPGRADING": "System is upgrading...", + "UPGRADE_FAILED": "Upgrade failed", + "ACTIVATION": "Activation", + "BATTERY_LOW": "Low battery", + "BATTERY_CHARGING": "Charging", + "BATTERY_FULL": "Battery full", + "BATTERY_NEED_CHARGE": "Low battery, please charge", + "VOLUME": "Volume ", + "MUTED": "Muted", + "MAX_VOLUME": "Max volume", + "RTC_MODE_OFF": "AEC Off", + "RTC_MODE_ON": "AEC On", + "PLEASE_WAIT": "Please wait...", + "FOUND_NEW_ASSETS": "Found new assets: %s", + "DOWNLOAD_ASSETS_FAILED": "Failed to download assets", + "LOADING_ASSETS": "Loading assets...", + "HELLO_MY_FRIEND": "Hello, my friend!" + } +} \ No newline at end of file diff --git a/main/assets/locales/en-US/upgrade.ogg b/main/assets/locales/en-US/upgrade.ogg new file mode 100644 index 0000000..f27ec7a Binary files /dev/null and b/main/assets/locales/en-US/upgrade.ogg differ diff --git a/main/assets/locales/en-US/welcome.ogg b/main/assets/locales/en-US/welcome.ogg new file mode 100644 index 0000000..4d4d8b9 Binary files /dev/null and b/main/assets/locales/en-US/welcome.ogg differ diff --git a/main/assets/locales/en-US/wificonfig.ogg b/main/assets/locales/en-US/wificonfig.ogg new file mode 100644 index 0000000..f4ed3d4 Binary files /dev/null and b/main/assets/locales/en-US/wificonfig.ogg differ diff --git a/main/assets/locales/es-ES/0.ogg b/main/assets/locales/es-ES/0.ogg new file mode 100644 index 0000000..98fbba2 Binary files /dev/null and b/main/assets/locales/es-ES/0.ogg differ diff --git a/main/assets/locales/es-ES/1.ogg b/main/assets/locales/es-ES/1.ogg new file mode 100644 index 0000000..2c2f4fb Binary files /dev/null and b/main/assets/locales/es-ES/1.ogg differ diff --git a/main/assets/locales/es-ES/2.ogg b/main/assets/locales/es-ES/2.ogg new file mode 100644 index 0000000..8e962b9 Binary files /dev/null and b/main/assets/locales/es-ES/2.ogg differ diff --git a/main/assets/locales/es-ES/3.ogg b/main/assets/locales/es-ES/3.ogg new file mode 100644 index 0000000..6b6ba47 Binary files /dev/null and b/main/assets/locales/es-ES/3.ogg differ diff --git a/main/assets/locales/es-ES/4.ogg b/main/assets/locales/es-ES/4.ogg new file mode 100644 index 0000000..ae5909c Binary files /dev/null and b/main/assets/locales/es-ES/4.ogg differ diff --git a/main/assets/locales/es-ES/5.ogg b/main/assets/locales/es-ES/5.ogg new file mode 100644 index 0000000..a8a4ca3 Binary files /dev/null and b/main/assets/locales/es-ES/5.ogg differ diff --git a/main/assets/locales/es-ES/6.ogg b/main/assets/locales/es-ES/6.ogg new file mode 100644 index 0000000..bcc46c0 Binary files /dev/null and b/main/assets/locales/es-ES/6.ogg differ diff --git a/main/assets/locales/es-ES/7.ogg b/main/assets/locales/es-ES/7.ogg new file mode 100644 index 0000000..09e7df4 Binary files /dev/null and b/main/assets/locales/es-ES/7.ogg differ diff --git a/main/assets/locales/es-ES/8.ogg b/main/assets/locales/es-ES/8.ogg new file mode 100644 index 0000000..e06e023 Binary files /dev/null and b/main/assets/locales/es-ES/8.ogg differ diff --git a/main/assets/locales/es-ES/9.ogg b/main/assets/locales/es-ES/9.ogg new file mode 100644 index 0000000..4108458 Binary files /dev/null and b/main/assets/locales/es-ES/9.ogg differ diff --git a/main/assets/locales/es-ES/activation.ogg b/main/assets/locales/es-ES/activation.ogg new file mode 100644 index 0000000..8d50682 Binary files /dev/null and b/main/assets/locales/es-ES/activation.ogg differ diff --git a/main/assets/locales/es-ES/err_pin.ogg b/main/assets/locales/es-ES/err_pin.ogg new file mode 100644 index 0000000..b3e55f8 Binary files /dev/null and b/main/assets/locales/es-ES/err_pin.ogg differ diff --git a/main/assets/locales/es-ES/err_reg.ogg b/main/assets/locales/es-ES/err_reg.ogg new file mode 100644 index 0000000..509451e Binary files /dev/null and b/main/assets/locales/es-ES/err_reg.ogg differ diff --git a/main/assets/locales/es-ES/language.json b/main/assets/locales/es-ES/language.json new file mode 100644 index 0000000..e7f349b --- /dev/null +++ b/main/assets/locales/es-ES/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "es-ES" + }, + "strings": { + "WARNING": "Advertencia", + "INFO": "Información", + "ERROR": "Error", + "VERSION": "Versión ", + "LOADING_PROTOCOL": "Conectando al servidor...", + "INITIALIZING": "Inicializando...", + "PIN_ERROR": "Por favor inserte la tarjeta SIM", + "REG_ERROR": "No se puede acceder a la red, verifique el estado de la tarjeta de datos", + "DETECTING_MODULE": "Detectando módulo...", + "REGISTERING_NETWORK": "Esperando red...", + "CHECKING_NEW_VERSION": "Verificando nueva versión...", + "CHECK_NEW_VERSION_FAILED": "Error al verificar nueva versión, reintentando en %d segundos: %s", + "SWITCH_TO_WIFI_NETWORK": "Cambiando a Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Cambiando a 4G...", + "STANDBY": "En espera", + "CONNECT_TO": "Conectar a ", + "CONNECTING": "Conectando...", + "CONNECTED_TO": "Conectado a ", + "LISTENING": "Escuchando...", + "SPEAKING": "Hablando...", + "SERVER_NOT_FOUND": "Buscando servicio disponible", + "SERVER_NOT_CONNECTED": "No se puede conectar al servicio, inténtelo más tarde", + "SERVER_TIMEOUT": "Tiempo de espera agotado", + "SERVER_ERROR": "Error de envío, verifique la red", + "CONNECT_TO_HOTSPOT": "Conectar teléfono al punto de acceso ", + "ACCESS_VIA_BROWSER": ",acceder mediante navegador ", + "WIFI_CONFIG_MODE": "Modo configuración de red", + "ENTERING_WIFI_CONFIG_MODE": "Entrando en modo configuración de red...", + "SCANNING_WIFI": "Escaneando Wi-Fi...", + "NEW_VERSION": "Nueva versión ", + "OTA_UPGRADE": "Actualización OTA", + "UPGRADING": "Actualizando sistema...", + "UPGRADE_FAILED": "Actualización fallida", + "ACTIVATION": "Activación del dispositivo", + "BATTERY_LOW": "Batería baja", + "BATTERY_CHARGING": "Cargando", + "BATTERY_FULL": "Batería llena", + "BATTERY_NEED_CHARGE": "Batería baja, por favor cargar", + "VOLUME": "Volumen ", + "MUTED": "Silenciado", + "MAX_VOLUME": "Volumen máximo", + "RTC_MODE_OFF": "AEC desactivado", + "RTC_MODE_ON": "AEC activado", + "DOWNLOAD_ASSETS_FAILED": "Error al descargar recursos", + "LOADING_ASSETS": "Cargando recursos...", + "PLEASE_WAIT": "Por favor espere...", + "FOUND_NEW_ASSETS": "Encontrados nuevos recursos: %s", + "HELLO_MY_FRIEND": "¡Hola, mi amigo!" + } +} \ No newline at end of file diff --git a/main/assets/locales/es-ES/upgrade.ogg b/main/assets/locales/es-ES/upgrade.ogg new file mode 100644 index 0000000..c29826c Binary files /dev/null and b/main/assets/locales/es-ES/upgrade.ogg differ diff --git a/main/assets/locales/es-ES/welcome.ogg b/main/assets/locales/es-ES/welcome.ogg new file mode 100644 index 0000000..a506db5 Binary files /dev/null and b/main/assets/locales/es-ES/welcome.ogg differ diff --git a/main/assets/locales/es-ES/wificonfig.ogg b/main/assets/locales/es-ES/wificonfig.ogg new file mode 100644 index 0000000..11755fa Binary files /dev/null and b/main/assets/locales/es-ES/wificonfig.ogg differ diff --git a/main/assets/locales/fa-IR/0.ogg b/main/assets/locales/fa-IR/0.ogg new file mode 100644 index 0000000..ed0881f Binary files /dev/null and b/main/assets/locales/fa-IR/0.ogg differ diff --git a/main/assets/locales/fa-IR/1.ogg b/main/assets/locales/fa-IR/1.ogg new file mode 100644 index 0000000..401059d Binary files /dev/null and b/main/assets/locales/fa-IR/1.ogg differ diff --git a/main/assets/locales/fa-IR/2.ogg b/main/assets/locales/fa-IR/2.ogg new file mode 100644 index 0000000..5ee8bfd Binary files /dev/null and b/main/assets/locales/fa-IR/2.ogg differ diff --git a/main/assets/locales/fa-IR/3.ogg b/main/assets/locales/fa-IR/3.ogg new file mode 100644 index 0000000..35d7e13 Binary files /dev/null and b/main/assets/locales/fa-IR/3.ogg differ diff --git a/main/assets/locales/fa-IR/4.ogg b/main/assets/locales/fa-IR/4.ogg new file mode 100644 index 0000000..5e19fe1 Binary files /dev/null and b/main/assets/locales/fa-IR/4.ogg differ diff --git a/main/assets/locales/fa-IR/5.ogg b/main/assets/locales/fa-IR/5.ogg new file mode 100644 index 0000000..2ac536b Binary files /dev/null and b/main/assets/locales/fa-IR/5.ogg differ diff --git a/main/assets/locales/fa-IR/6.ogg b/main/assets/locales/fa-IR/6.ogg new file mode 100644 index 0000000..6b9f40a Binary files /dev/null and b/main/assets/locales/fa-IR/6.ogg differ diff --git a/main/assets/locales/fa-IR/7.ogg b/main/assets/locales/fa-IR/7.ogg new file mode 100644 index 0000000..568e6c3 Binary files /dev/null and b/main/assets/locales/fa-IR/7.ogg differ diff --git a/main/assets/locales/fa-IR/8.ogg b/main/assets/locales/fa-IR/8.ogg new file mode 100644 index 0000000..055f395 Binary files /dev/null and b/main/assets/locales/fa-IR/8.ogg differ diff --git a/main/assets/locales/fa-IR/9.ogg b/main/assets/locales/fa-IR/9.ogg new file mode 100644 index 0000000..42023e8 Binary files /dev/null and b/main/assets/locales/fa-IR/9.ogg differ diff --git a/main/assets/locales/fa-IR/activation.ogg b/main/assets/locales/fa-IR/activation.ogg new file mode 100644 index 0000000..6bce7f9 Binary files /dev/null and b/main/assets/locales/fa-IR/activation.ogg differ diff --git a/main/assets/locales/fa-IR/err_pin.ogg b/main/assets/locales/fa-IR/err_pin.ogg new file mode 100644 index 0000000..0450947 Binary files /dev/null and b/main/assets/locales/fa-IR/err_pin.ogg differ diff --git a/main/assets/locales/fa-IR/err_reg.ogg b/main/assets/locales/fa-IR/err_reg.ogg new file mode 100644 index 0000000..d293376 Binary files /dev/null and b/main/assets/locales/fa-IR/err_reg.ogg differ diff --git a/main/assets/locales/fa-IR/language.json b/main/assets/locales/fa-IR/language.json new file mode 100644 index 0000000..784f6bd --- /dev/null +++ b/main/assets/locales/fa-IR/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "fa-IR" + }, + "strings": { + "WARNING": "هشدار", + "INFO": "اطلاعات", + "ERROR": "خطا", + "VERSION": "نسخه ", + "LOADING_PROTOCOL": "ورود به سیستم...", + "INITIALIZING": "در حال راه‌اندازی...", + "PIN_ERROR": "لطفاً سیم کارت را وارد کنید", + "REG_ERROR": "عدم دسترسی به شبکه، لطفاً وضعیت سیم کارت را بررسی کنید", + "DETECTING_MODULE": "شناسایی ماژول...", + "REGISTERING_NETWORK": "در انتظار شبکه...", + "CHECKING_NEW_VERSION": "بررسی نسخه جدید...", + "CHECK_NEW_VERSION_FAILED": "بررسی نسخه جدید ناموفق بود، پس از %d ثانیه مجدداً تلاش می‌شود: %s", + "SWITCH_TO_WIFI_NETWORK": "تغییر به Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "تغییر به 4G...", + "STANDBY": "آماده به کار", + "CONNECT_TO": "اتصال به ", + "CONNECTING": "در حال اتصال...", + "CONNECTION_SUCCESSFUL": "اتصال موفق", + "CONNECTED_TO": "متصل به ", + "LISTENING": "در حال گوش دادن...", + "SPEAKING": "در حال صحبت...", + "SERVER_NOT_FOUND": "جستجوی سرویس در دسترس", + "SERVER_NOT_CONNECTED": "اتصال به سرویس برقرار نشد، لطفاً بعداً تلاش کنید", + "SERVER_TIMEOUT": "زمان انتظار برای پاسخ به پایان رسید", + "SERVER_ERROR": "ارسال ناموفق، لطفاً شبکه را بررسی کنید", + "CONNECT_TO_HOTSPOT": "نقطه اتصال: ", + "ACCESS_VIA_BROWSER": " آدرس پیکربندی: ", + "WIFI_CONFIG_MODE": "حالت پیکربندی Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "ورود به حالت پیکربندی Wi-Fi...", + "SCANNING_WIFI": "جستجوی Wi-Fi...", + "NEW_VERSION": "نسخه جدید ", + "OTA_UPGRADE": "به‌روزرسانی OTA", + "UPGRADING": "سیستم در حال به‌روزرسانی است...", + "UPGRADE_FAILED": "به‌روزرسانی ناموفق بود", + "ACTIVATION": "فعال‌سازی", + "BATTERY_LOW": "شارژ باتری کم", + "BATTERY_CHARGING": "در حال شارژ", + "BATTERY_FULL": "باتری پر است", + "BATTERY_NEED_CHARGE": "شارژ باتری کم، لطفاً شارژ کنید", + "VOLUME": "صدا ", + "MUTED": "بی‌صدا", + "MAX_VOLUME": "حداکثر صدا", + "RTC_MODE_OFF": "AEC خاموش", + "RTC_MODE_ON": "AEC روشن", + "PLEASE_WAIT": "لطفاً صبر کنید...", + "FOUND_NEW_ASSETS": "منابع جدید یافت شد: %s", + "DOWNLOAD_ASSETS_FAILED": "دانلود منابع ناموفق بود", + "LOADING_ASSETS": "بارگذاری منابع...", + "HELLO_MY_FRIEND": "سلام، دوست من!" + } +} + diff --git a/main/assets/locales/fa-IR/upgrade.ogg b/main/assets/locales/fa-IR/upgrade.ogg new file mode 100644 index 0000000..9eff121 Binary files /dev/null and b/main/assets/locales/fa-IR/upgrade.ogg differ diff --git a/main/assets/locales/fa-IR/welcome.ogg b/main/assets/locales/fa-IR/welcome.ogg new file mode 100644 index 0000000..108a62d Binary files /dev/null and b/main/assets/locales/fa-IR/welcome.ogg differ diff --git a/main/assets/locales/fa-IR/wificonfig.ogg b/main/assets/locales/fa-IR/wificonfig.ogg new file mode 100644 index 0000000..179fa5e Binary files /dev/null and b/main/assets/locales/fa-IR/wificonfig.ogg differ diff --git a/main/assets/locales/fi-FI/0.ogg b/main/assets/locales/fi-FI/0.ogg new file mode 100644 index 0000000..d368787 Binary files /dev/null and b/main/assets/locales/fi-FI/0.ogg differ diff --git a/main/assets/locales/fi-FI/1.ogg b/main/assets/locales/fi-FI/1.ogg new file mode 100644 index 0000000..f496dd6 Binary files /dev/null and b/main/assets/locales/fi-FI/1.ogg differ diff --git a/main/assets/locales/fi-FI/2.ogg b/main/assets/locales/fi-FI/2.ogg new file mode 100644 index 0000000..96a2529 Binary files /dev/null and b/main/assets/locales/fi-FI/2.ogg differ diff --git a/main/assets/locales/fi-FI/3.ogg b/main/assets/locales/fi-FI/3.ogg new file mode 100644 index 0000000..1fcdcf2 Binary files /dev/null and b/main/assets/locales/fi-FI/3.ogg differ diff --git a/main/assets/locales/fi-FI/4.ogg b/main/assets/locales/fi-FI/4.ogg new file mode 100644 index 0000000..6ba9ded Binary files /dev/null and b/main/assets/locales/fi-FI/4.ogg differ diff --git a/main/assets/locales/fi-FI/5.ogg b/main/assets/locales/fi-FI/5.ogg new file mode 100644 index 0000000..b94d4a2 Binary files /dev/null and b/main/assets/locales/fi-FI/5.ogg differ diff --git a/main/assets/locales/fi-FI/6.ogg b/main/assets/locales/fi-FI/6.ogg new file mode 100644 index 0000000..ffe8276 Binary files /dev/null and b/main/assets/locales/fi-FI/6.ogg differ diff --git a/main/assets/locales/fi-FI/7.ogg b/main/assets/locales/fi-FI/7.ogg new file mode 100644 index 0000000..ed3197a Binary files /dev/null and b/main/assets/locales/fi-FI/7.ogg differ diff --git a/main/assets/locales/fi-FI/8.ogg b/main/assets/locales/fi-FI/8.ogg new file mode 100644 index 0000000..7f81a62 Binary files /dev/null and b/main/assets/locales/fi-FI/8.ogg differ diff --git a/main/assets/locales/fi-FI/9.ogg b/main/assets/locales/fi-FI/9.ogg new file mode 100644 index 0000000..aaedd05 Binary files /dev/null and b/main/assets/locales/fi-FI/9.ogg differ diff --git a/main/assets/locales/fi-FI/activation.ogg b/main/assets/locales/fi-FI/activation.ogg new file mode 100644 index 0000000..6347745 Binary files /dev/null and b/main/assets/locales/fi-FI/activation.ogg differ diff --git a/main/assets/locales/fi-FI/err_pin.ogg b/main/assets/locales/fi-FI/err_pin.ogg new file mode 100644 index 0000000..8c6eb51 Binary files /dev/null and b/main/assets/locales/fi-FI/err_pin.ogg differ diff --git a/main/assets/locales/fi-FI/err_reg.ogg b/main/assets/locales/fi-FI/err_reg.ogg new file mode 100644 index 0000000..32561bf Binary files /dev/null and b/main/assets/locales/fi-FI/err_reg.ogg differ diff --git a/main/assets/locales/fi-FI/language.json b/main/assets/locales/fi-FI/language.json new file mode 100644 index 0000000..2326ee4 --- /dev/null +++ b/main/assets/locales/fi-FI/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "fi-FI" + }, + "strings": { + "WARNING": "Varoitus", + "INFO": "Tieto", + "ERROR": "Virhe", + "VERSION": "Versio ", + "LOADING_PROTOCOL": "Yhdistetään palvelimeen...", + "INITIALIZING": "Alustetaan...", + "PIN_ERROR": "Ole hyvä ja aseta SIM-kortti", + "REG_ERROR": "Ei voi muodostaa yhteyttä verkkoon, tarkista datakortin tila", + "DETECTING_MODULE": "Tunnistetaan moduuli...", + "REGISTERING_NETWORK": "Odotetaan verkkoa...", + "CHECKING_NEW_VERSION": "Tarkistetaan uutta versiota...", + "CHECK_NEW_VERSION_FAILED": "Uuden version tarkistus epäonnistui, yritetään uudelleen %d sekunnin kuluttua: %s", + "SWITCH_TO_WIFI_NETWORK": "Vaihdetaan Wi-Fi:hin...", + "SWITCH_TO_4G_NETWORK": "Vaihdetaan 4G:hen...", + "STANDBY": "Valmiustila", + "CONNECT_TO": "Yhdistä ", + "CONNECTING": "Yhdistetään...", + "CONNECTED_TO": "Yhdistetty ", + "LISTENING": "Kuunnellaan...", + "SPEAKING": "Puhutaan...", + "SERVER_NOT_FOUND": "Etsitään käytettävissä olevaa palvelua", + "SERVER_NOT_CONNECTED": "Ei voi yhdistää palveluun, yritä myöhemmin", + "SERVER_TIMEOUT": "Vastauksen aikakatkaisu", + "SERVER_ERROR": "Lähetys epäonnistui, tarkista verkko", + "CONNECT_TO_HOTSPOT": "Yhdistä puhelin hotspottiin ", + "ACCESS_VIA_BROWSER": ",pääsy selaimen kautta ", + "WIFI_CONFIG_MODE": "Verkon konfigurointitila", + "ENTERING_WIFI_CONFIG_MODE": "Siirrytään verkon konfigurointitilaan...", + "SCANNING_WIFI": "Skannataan Wi-Fi...", + "NEW_VERSION": "Uusi versio ", + "OTA_UPGRADE": "OTA-päivitys", + "UPGRADING": "Päivitetään järjestelmää...", + "UPGRADE_FAILED": "Päivitys epäonnistui", + "ACTIVATION": "Laitteen aktivointi", + "BATTERY_LOW": "Akku vähissä", + "BATTERY_CHARGING": "Ladataan", + "BATTERY_FULL": "Akku täynnä", + "BATTERY_NEED_CHARGE": "Akku vähissä, ole hyvä ja lataa", + "VOLUME": "Äänenvoimakkuus ", + "MUTED": "Mykistetty", + "MAX_VOLUME": "Maksimi äänenvoimakkuus", + "RTC_MODE_OFF": "AEC pois päältä", + "RTC_MODE_ON": "AEC päällä", + "DOWNLOAD_ASSETS_FAILED": "Resurssien lataaminen epäonnistui", + "LOADING_ASSETS": "Ladataan resursseja...", + "PLEASE_WAIT": "Odota hetki...", + "FOUND_NEW_ASSETS": "Löydetty uusia resursseja: %s", + "HELLO_MY_FRIEND": "Hei, ystäväni!" + } +} \ No newline at end of file diff --git a/main/assets/locales/fi-FI/upgrade.ogg b/main/assets/locales/fi-FI/upgrade.ogg new file mode 100644 index 0000000..5ff02a6 Binary files /dev/null and b/main/assets/locales/fi-FI/upgrade.ogg differ diff --git a/main/assets/locales/fi-FI/welcome.ogg b/main/assets/locales/fi-FI/welcome.ogg new file mode 100644 index 0000000..1430372 Binary files /dev/null and b/main/assets/locales/fi-FI/welcome.ogg differ diff --git a/main/assets/locales/fi-FI/wificonfig.ogg b/main/assets/locales/fi-FI/wificonfig.ogg new file mode 100644 index 0000000..deb233a Binary files /dev/null and b/main/assets/locales/fi-FI/wificonfig.ogg differ diff --git a/main/assets/locales/fil-PH/0.ogg b/main/assets/locales/fil-PH/0.ogg new file mode 100644 index 0000000..1f8c2fc Binary files /dev/null and b/main/assets/locales/fil-PH/0.ogg differ diff --git a/main/assets/locales/fil-PH/1.ogg b/main/assets/locales/fil-PH/1.ogg new file mode 100644 index 0000000..bc38364 Binary files /dev/null and b/main/assets/locales/fil-PH/1.ogg differ diff --git a/main/assets/locales/fil-PH/2.ogg b/main/assets/locales/fil-PH/2.ogg new file mode 100644 index 0000000..01cb65b Binary files /dev/null and b/main/assets/locales/fil-PH/2.ogg differ diff --git a/main/assets/locales/fil-PH/3.ogg b/main/assets/locales/fil-PH/3.ogg new file mode 100644 index 0000000..0f40545 Binary files /dev/null and b/main/assets/locales/fil-PH/3.ogg differ diff --git a/main/assets/locales/fil-PH/4.ogg b/main/assets/locales/fil-PH/4.ogg new file mode 100644 index 0000000..a476dc3 Binary files /dev/null and b/main/assets/locales/fil-PH/4.ogg differ diff --git a/main/assets/locales/fil-PH/5.ogg b/main/assets/locales/fil-PH/5.ogg new file mode 100644 index 0000000..1c39dab Binary files /dev/null and b/main/assets/locales/fil-PH/5.ogg differ diff --git a/main/assets/locales/fil-PH/6.ogg b/main/assets/locales/fil-PH/6.ogg new file mode 100644 index 0000000..b672cbd Binary files /dev/null and b/main/assets/locales/fil-PH/6.ogg differ diff --git a/main/assets/locales/fil-PH/7.ogg b/main/assets/locales/fil-PH/7.ogg new file mode 100644 index 0000000..f02aa1e Binary files /dev/null and b/main/assets/locales/fil-PH/7.ogg differ diff --git a/main/assets/locales/fil-PH/8.ogg b/main/assets/locales/fil-PH/8.ogg new file mode 100644 index 0000000..b699c1e Binary files /dev/null and b/main/assets/locales/fil-PH/8.ogg differ diff --git a/main/assets/locales/fil-PH/9.ogg b/main/assets/locales/fil-PH/9.ogg new file mode 100644 index 0000000..fc0adc8 Binary files /dev/null and b/main/assets/locales/fil-PH/9.ogg differ diff --git a/main/assets/locales/fil-PH/activation.ogg b/main/assets/locales/fil-PH/activation.ogg new file mode 100644 index 0000000..d8b6a62 Binary files /dev/null and b/main/assets/locales/fil-PH/activation.ogg differ diff --git a/main/assets/locales/fil-PH/err_pin.ogg b/main/assets/locales/fil-PH/err_pin.ogg new file mode 100644 index 0000000..527ca8c Binary files /dev/null and b/main/assets/locales/fil-PH/err_pin.ogg differ diff --git a/main/assets/locales/fil-PH/err_reg.ogg b/main/assets/locales/fil-PH/err_reg.ogg new file mode 100644 index 0000000..94632fc Binary files /dev/null and b/main/assets/locales/fil-PH/err_reg.ogg differ diff --git a/main/assets/locales/fil-PH/language.json b/main/assets/locales/fil-PH/language.json new file mode 100644 index 0000000..2d35fc5 --- /dev/null +++ b/main/assets/locales/fil-PH/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "fil-PH" + }, + "strings": { + "WARNING": "Babala", + "INFO": "Impormasyon", + "ERROR": "Error", + "VERSION": "Bersyon ", + "LOADING_PROTOCOL": "Nagla-log in...", + "INITIALIZING": "Nag-i-initialize...", + "PIN_ERROR": "Mangyaring ilagay ang SIM card", + "REG_ERROR": "Hindi ma-access ang network, mangyaring tingnan ang estado ng SIM card", + "DETECTING_MODULE": "Tinutuklas ang module...", + "REGISTERING_NETWORK": "Naghihintay ng network...", + "CHECKING_NEW_VERSION": "Sinusuri ang bagong bersyon...", + "CHECK_NEW_VERSION_FAILED": "Nabigo ang pagsuri ng bagong bersyon, susubukan muli sa %d segundo: %s", + "SWITCH_TO_WIFI_NETWORK": "Lumilipat sa Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Lumilipat sa 4G...", + "STANDBY": "Standby", + "CONNECT_TO": "Kumonekta sa ", + "CONNECTING": "Kumokonekta...", + "CONNECTION_SUCCESSFUL": "Matagumpay na koneksyon", + "CONNECTED_TO": "Nakakonekta sa ", + "LISTENING": "Nakikinig...", + "SPEAKING": "Nagsasalita...", + "SERVER_NOT_FOUND": "Naghahanap ng available na serbisyo", + "SERVER_NOT_CONNECTED": "Hindi makakonekta sa serbisyo, mangyaring subukan muli mamaya", + "SERVER_TIMEOUT": "Nag-timeout ang paghihintay ng tugon", + "SERVER_ERROR": "Nabigo ang pagpapadala, mangyaring tingnan ang network", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " URL ng configuration: ", + "WIFI_CONFIG_MODE": "Wi-Fi Configuration Mode", + "ENTERING_WIFI_CONFIG_MODE": "Pumapasok sa Wi-Fi configuration mode...", + "SCANNING_WIFI": "Nag-i-scan ng Wi-Fi...", + "NEW_VERSION": "Bagong bersyon ", + "OTA_UPGRADE": "OTA Upgrade", + "UPGRADING": "Nag-a-upgrade ang system...", + "UPGRADE_FAILED": "Nabigo ang upgrade", + "ACTIVATION": "Activation", + "BATTERY_LOW": "Mababang baterya", + "BATTERY_CHARGING": "Nagcha-charge", + "BATTERY_FULL": "Puno ang baterya", + "BATTERY_NEED_CHARGE": "Mababang baterya, mangyaring mag-charge", + "VOLUME": "Volume ", + "MUTED": "Naka-mute", + "MAX_VOLUME": "Maximum volume", + "RTC_MODE_OFF": "AEC Off", + "RTC_MODE_ON": "AEC On", + "PLEASE_WAIT": "Mangyaring maghintay...", + "FOUND_NEW_ASSETS": "Nakahanap ng mga bagong assets: %s", + "DOWNLOAD_ASSETS_FAILED": "Nabigo ang pag-download ng mga assets", + "LOADING_ASSETS": "Nilo-load ang mga assets...", + "HELLO_MY_FRIEND": "Kumusta, kaibigan ko!" + } +} + diff --git a/main/assets/locales/fil-PH/upgrade.ogg b/main/assets/locales/fil-PH/upgrade.ogg new file mode 100644 index 0000000..8930d78 Binary files /dev/null and b/main/assets/locales/fil-PH/upgrade.ogg differ diff --git a/main/assets/locales/fil-PH/welcome.ogg b/main/assets/locales/fil-PH/welcome.ogg new file mode 100644 index 0000000..ed59bce Binary files /dev/null and b/main/assets/locales/fil-PH/welcome.ogg differ diff --git a/main/assets/locales/fil-PH/wificonfig.ogg b/main/assets/locales/fil-PH/wificonfig.ogg new file mode 100644 index 0000000..cef030d Binary files /dev/null and b/main/assets/locales/fil-PH/wificonfig.ogg differ diff --git a/main/assets/locales/fr-FR/0.ogg b/main/assets/locales/fr-FR/0.ogg new file mode 100644 index 0000000..79b8faf Binary files /dev/null and b/main/assets/locales/fr-FR/0.ogg differ diff --git a/main/assets/locales/fr-FR/1.ogg b/main/assets/locales/fr-FR/1.ogg new file mode 100644 index 0000000..e517324 Binary files /dev/null and b/main/assets/locales/fr-FR/1.ogg differ diff --git a/main/assets/locales/fr-FR/2.ogg b/main/assets/locales/fr-FR/2.ogg new file mode 100644 index 0000000..311697c Binary files /dev/null and b/main/assets/locales/fr-FR/2.ogg differ diff --git a/main/assets/locales/fr-FR/3.ogg b/main/assets/locales/fr-FR/3.ogg new file mode 100644 index 0000000..5b4acc1 Binary files /dev/null and b/main/assets/locales/fr-FR/3.ogg differ diff --git a/main/assets/locales/fr-FR/4.ogg b/main/assets/locales/fr-FR/4.ogg new file mode 100644 index 0000000..832aeab Binary files /dev/null and b/main/assets/locales/fr-FR/4.ogg differ diff --git a/main/assets/locales/fr-FR/5.ogg b/main/assets/locales/fr-FR/5.ogg new file mode 100644 index 0000000..ddcce17 Binary files /dev/null and b/main/assets/locales/fr-FR/5.ogg differ diff --git a/main/assets/locales/fr-FR/6.ogg b/main/assets/locales/fr-FR/6.ogg new file mode 100644 index 0000000..aced771 Binary files /dev/null and b/main/assets/locales/fr-FR/6.ogg differ diff --git a/main/assets/locales/fr-FR/7.ogg b/main/assets/locales/fr-FR/7.ogg new file mode 100644 index 0000000..293d1c0 Binary files /dev/null and b/main/assets/locales/fr-FR/7.ogg differ diff --git a/main/assets/locales/fr-FR/8.ogg b/main/assets/locales/fr-FR/8.ogg new file mode 100644 index 0000000..acec112 Binary files /dev/null and b/main/assets/locales/fr-FR/8.ogg differ diff --git a/main/assets/locales/fr-FR/9.ogg b/main/assets/locales/fr-FR/9.ogg new file mode 100644 index 0000000..fe27acd Binary files /dev/null and b/main/assets/locales/fr-FR/9.ogg differ diff --git a/main/assets/locales/fr-FR/activation.ogg b/main/assets/locales/fr-FR/activation.ogg new file mode 100644 index 0000000..b48f215 Binary files /dev/null and b/main/assets/locales/fr-FR/activation.ogg differ diff --git a/main/assets/locales/fr-FR/err_pin.ogg b/main/assets/locales/fr-FR/err_pin.ogg new file mode 100644 index 0000000..1a3d84b Binary files /dev/null and b/main/assets/locales/fr-FR/err_pin.ogg differ diff --git a/main/assets/locales/fr-FR/err_reg.ogg b/main/assets/locales/fr-FR/err_reg.ogg new file mode 100644 index 0000000..c3256c5 Binary files /dev/null and b/main/assets/locales/fr-FR/err_reg.ogg differ diff --git a/main/assets/locales/fr-FR/language.json b/main/assets/locales/fr-FR/language.json new file mode 100644 index 0000000..244cade --- /dev/null +++ b/main/assets/locales/fr-FR/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "fr-FR" + }, + "strings": { + "WARNING": "Avertissement", + "INFO": "Information", + "ERROR": "Erreur", + "VERSION": "Version ", + "LOADING_PROTOCOL": "Connexion au serveur...", + "INITIALIZING": "Initialisation...", + "PIN_ERROR": "Veuillez insérer la carte SIM", + "REG_ERROR": "Impossible d'accéder au réseau, veuillez vérifier l'état de la carte de données", + "DETECTING_MODULE": "Détection du module...", + "REGISTERING_NETWORK": "En attente du réseau...", + "CHECKING_NEW_VERSION": "Vérification de nouvelle version...", + "CHECK_NEW_VERSION_FAILED": "Échec de vérification de nouvelle version, nouvelle tentative dans %d secondes : %s", + "SWITCH_TO_WIFI_NETWORK": "Basculer vers Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Basculer vers 4G...", + "STANDBY": "En attente", + "CONNECT_TO": "Se connecter à ", + "CONNECTING": "Connexion en cours...", + "CONNECTED_TO": "Connecté à ", + "LISTENING": "Écoute...", + "SPEAKING": "Parole...", + "SERVER_NOT_FOUND": "Recherche d'un service disponible", + "SERVER_NOT_CONNECTED": "Impossible de se connecter au service, veuillez réessayer plus tard", + "SERVER_TIMEOUT": "Délai d'attente de réponse", + "SERVER_ERROR": "Échec d'envoi, veuillez vérifier le réseau", + "CONNECT_TO_HOTSPOT": "Connecter le téléphone au point d'accès ", + "ACCESS_VIA_BROWSER": ",accéder via le navigateur ", + "WIFI_CONFIG_MODE": "Mode configuration réseau", + "ENTERING_WIFI_CONFIG_MODE": "Entrer en mode configuration réseau...", + "SCANNING_WIFI": "Scan Wi-Fi...", + "NEW_VERSION": "Nouvelle version ", + "OTA_UPGRADE": "Mise à jour OTA", + "UPGRADING": "Mise à jour du système...", + "UPGRADE_FAILED": "Échec de mise à jour", + "ACTIVATION": "Activation de l'appareil", + "BATTERY_LOW": "Batterie faible", + "BATTERY_CHARGING": "En charge", + "BATTERY_FULL": "Batterie pleine", + "BATTERY_NEED_CHARGE": "Batterie faible, veuillez charger", + "VOLUME": "Volume ", + "MUTED": "Muet", + "MAX_VOLUME": "Volume maximum", + "RTC_MODE_OFF": "AEC désactivé", + "RTC_MODE_ON": "AEC activé", + "DOWNLOAD_ASSETS_FAILED": "Échec du téléchargement des ressources", + "LOADING_ASSETS": "Chargement des ressources...", + "PLEASE_WAIT": "Veuillez patienter...", + "FOUND_NEW_ASSETS": "Nouvelles ressources trouvées: %s", + "HELLO_MY_FRIEND": "Bonjour, mon ami !" + } +} \ No newline at end of file diff --git a/main/assets/locales/fr-FR/upgrade.ogg b/main/assets/locales/fr-FR/upgrade.ogg new file mode 100644 index 0000000..b6ac1f9 Binary files /dev/null and b/main/assets/locales/fr-FR/upgrade.ogg differ diff --git a/main/assets/locales/fr-FR/welcome.ogg b/main/assets/locales/fr-FR/welcome.ogg new file mode 100644 index 0000000..4492de7 Binary files /dev/null and b/main/assets/locales/fr-FR/welcome.ogg differ diff --git a/main/assets/locales/fr-FR/wificonfig.ogg b/main/assets/locales/fr-FR/wificonfig.ogg new file mode 100644 index 0000000..9e2f99b Binary files /dev/null and b/main/assets/locales/fr-FR/wificonfig.ogg differ diff --git a/main/assets/locales/he-IL/0.ogg b/main/assets/locales/he-IL/0.ogg new file mode 100644 index 0000000..efea905 Binary files /dev/null and b/main/assets/locales/he-IL/0.ogg differ diff --git a/main/assets/locales/he-IL/1.ogg b/main/assets/locales/he-IL/1.ogg new file mode 100644 index 0000000..b0984b6 Binary files /dev/null and b/main/assets/locales/he-IL/1.ogg differ diff --git a/main/assets/locales/he-IL/2.ogg b/main/assets/locales/he-IL/2.ogg new file mode 100644 index 0000000..c70358a Binary files /dev/null and b/main/assets/locales/he-IL/2.ogg differ diff --git a/main/assets/locales/he-IL/3.ogg b/main/assets/locales/he-IL/3.ogg new file mode 100644 index 0000000..0398e82 Binary files /dev/null and b/main/assets/locales/he-IL/3.ogg differ diff --git a/main/assets/locales/he-IL/4.ogg b/main/assets/locales/he-IL/4.ogg new file mode 100644 index 0000000..78630a6 Binary files /dev/null and b/main/assets/locales/he-IL/4.ogg differ diff --git a/main/assets/locales/he-IL/5.ogg b/main/assets/locales/he-IL/5.ogg new file mode 100644 index 0000000..f8bd938 Binary files /dev/null and b/main/assets/locales/he-IL/5.ogg differ diff --git a/main/assets/locales/he-IL/6.ogg b/main/assets/locales/he-IL/6.ogg new file mode 100644 index 0000000..d30c9e5 Binary files /dev/null and b/main/assets/locales/he-IL/6.ogg differ diff --git a/main/assets/locales/he-IL/7.ogg b/main/assets/locales/he-IL/7.ogg new file mode 100644 index 0000000..610c469 Binary files /dev/null and b/main/assets/locales/he-IL/7.ogg differ diff --git a/main/assets/locales/he-IL/8.ogg b/main/assets/locales/he-IL/8.ogg new file mode 100644 index 0000000..ce834f6 Binary files /dev/null and b/main/assets/locales/he-IL/8.ogg differ diff --git a/main/assets/locales/he-IL/9.ogg b/main/assets/locales/he-IL/9.ogg new file mode 100644 index 0000000..d452e95 Binary files /dev/null and b/main/assets/locales/he-IL/9.ogg differ diff --git a/main/assets/locales/he-IL/activation.ogg b/main/assets/locales/he-IL/activation.ogg new file mode 100644 index 0000000..31eb4ac Binary files /dev/null and b/main/assets/locales/he-IL/activation.ogg differ diff --git a/main/assets/locales/he-IL/err_pin.ogg b/main/assets/locales/he-IL/err_pin.ogg new file mode 100644 index 0000000..5943f96 Binary files /dev/null and b/main/assets/locales/he-IL/err_pin.ogg differ diff --git a/main/assets/locales/he-IL/err_reg.ogg b/main/assets/locales/he-IL/err_reg.ogg new file mode 100644 index 0000000..a860ec1 Binary files /dev/null and b/main/assets/locales/he-IL/err_reg.ogg differ diff --git a/main/assets/locales/he-IL/language.json b/main/assets/locales/he-IL/language.json new file mode 100644 index 0000000..e3570c0 --- /dev/null +++ b/main/assets/locales/he-IL/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "he-IL" + }, + "strings": { + "WARNING": "אזהרה", + "INFO": "מידע", + "ERROR": "שגיאה", + "VERSION": "גרסה ", + "LOADING_PROTOCOL": "מתחבר...", + "INITIALIZING": "מאתחל...", + "PIN_ERROR": "אנא הכנס כרטיס SIM", + "REG_ERROR": "לא ניתן לגשת לרשת, אנא בדוק את מצב כרטיס ה-SIM", + "DETECTING_MODULE": "מזהה מודול...", + "REGISTERING_NETWORK": "ממתין לרשת...", + "CHECKING_NEW_VERSION": "בודק גרסה חדשה...", + "CHECK_NEW_VERSION_FAILED": "בדיקת גרסה חדשה נכשלה, ינסה שוב בעוד %d שניות: %s", + "SWITCH_TO_WIFI_NETWORK": "עובר ל-Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "עובר ל-4G...", + "STANDBY": "המתנה", + "CONNECT_TO": "התחבר ל-", + "CONNECTING": "מתחבר...", + "CONNECTION_SUCCESSFUL": "התחברות הצליחה", + "CONNECTED_TO": "מחובר ל-", + "LISTENING": "מקשיב...", + "SPEAKING": "מדבר...", + "SERVER_NOT_FOUND": "מחפש שירות זמין", + "SERVER_NOT_CONNECTED": "לא ניתן להתחבר לשירות, אנא נסה שוב מאוחר יותר", + "SERVER_TIMEOUT": "פג זמן ההמתנה לתגובה", + "SERVER_ERROR": "השליחה נכשלה, אנא בדוק את הרשת", + "CONNECT_TO_HOTSPOT": "נקודה חמה: ", + "ACCESS_VIA_BROWSER": " כתובת תצורה: ", + "WIFI_CONFIG_MODE": "מצב תצורת Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "נכנס למצב תצורת Wi-Fi...", + "SCANNING_WIFI": "סורק Wi-Fi...", + "NEW_VERSION": "גרסה חדשה ", + "OTA_UPGRADE": "שדרוג OTA", + "UPGRADING": "המערכת משתדרגת...", + "UPGRADE_FAILED": "השדרוג נכשל", + "ACTIVATION": "הפעלה", + "BATTERY_LOW": "סוללה חלשה", + "BATTERY_CHARGING": "נטען", + "BATTERY_FULL": "הסוללה מלאה", + "BATTERY_NEED_CHARGE": "סוללה חלשה, אנא טען", + "VOLUME": "עוצמת קול ", + "MUTED": "מושתק", + "MAX_VOLUME": "עוצמת קול מקסימלית", + "RTC_MODE_OFF": "AEC כבוי", + "RTC_MODE_ON": "AEC דלוק", + "PLEASE_WAIT": "אנא המתן...", + "FOUND_NEW_ASSETS": "נמצאו משאבים חדשים: %s", + "DOWNLOAD_ASSETS_FAILED": "הורדת משאבים נכשלה", + "LOADING_ASSETS": "טוען משאבים...", + "HELLO_MY_FRIEND": "שלום, ידידי!" + } +} + diff --git a/main/assets/locales/he-IL/upgrade.ogg b/main/assets/locales/he-IL/upgrade.ogg new file mode 100644 index 0000000..ff36a86 Binary files /dev/null and b/main/assets/locales/he-IL/upgrade.ogg differ diff --git a/main/assets/locales/he-IL/welcome.ogg b/main/assets/locales/he-IL/welcome.ogg new file mode 100644 index 0000000..6594d37 Binary files /dev/null and b/main/assets/locales/he-IL/welcome.ogg differ diff --git a/main/assets/locales/he-IL/wificonfig.ogg b/main/assets/locales/he-IL/wificonfig.ogg new file mode 100644 index 0000000..6cf0597 Binary files /dev/null and b/main/assets/locales/he-IL/wificonfig.ogg differ diff --git a/main/assets/locales/hi-IN/0.ogg b/main/assets/locales/hi-IN/0.ogg new file mode 100644 index 0000000..e531348 Binary files /dev/null and b/main/assets/locales/hi-IN/0.ogg differ diff --git a/main/assets/locales/hi-IN/1.ogg b/main/assets/locales/hi-IN/1.ogg new file mode 100644 index 0000000..cb2f9d5 Binary files /dev/null and b/main/assets/locales/hi-IN/1.ogg differ diff --git a/main/assets/locales/hi-IN/2.ogg b/main/assets/locales/hi-IN/2.ogg new file mode 100644 index 0000000..2244d45 Binary files /dev/null and b/main/assets/locales/hi-IN/2.ogg differ diff --git a/main/assets/locales/hi-IN/3.ogg b/main/assets/locales/hi-IN/3.ogg new file mode 100644 index 0000000..63fde6d Binary files /dev/null and b/main/assets/locales/hi-IN/3.ogg differ diff --git a/main/assets/locales/hi-IN/4.ogg b/main/assets/locales/hi-IN/4.ogg new file mode 100644 index 0000000..76caee9 Binary files /dev/null and b/main/assets/locales/hi-IN/4.ogg differ diff --git a/main/assets/locales/hi-IN/5.ogg b/main/assets/locales/hi-IN/5.ogg new file mode 100644 index 0000000..c96a386 Binary files /dev/null and b/main/assets/locales/hi-IN/5.ogg differ diff --git a/main/assets/locales/hi-IN/6.ogg b/main/assets/locales/hi-IN/6.ogg new file mode 100644 index 0000000..88f7643 Binary files /dev/null and b/main/assets/locales/hi-IN/6.ogg differ diff --git a/main/assets/locales/hi-IN/7.ogg b/main/assets/locales/hi-IN/7.ogg new file mode 100644 index 0000000..3a997d4 Binary files /dev/null and b/main/assets/locales/hi-IN/7.ogg differ diff --git a/main/assets/locales/hi-IN/8.ogg b/main/assets/locales/hi-IN/8.ogg new file mode 100644 index 0000000..56f125e Binary files /dev/null and b/main/assets/locales/hi-IN/8.ogg differ diff --git a/main/assets/locales/hi-IN/9.ogg b/main/assets/locales/hi-IN/9.ogg new file mode 100644 index 0000000..25e64c0 Binary files /dev/null and b/main/assets/locales/hi-IN/9.ogg differ diff --git a/main/assets/locales/hi-IN/activation.ogg b/main/assets/locales/hi-IN/activation.ogg new file mode 100644 index 0000000..aa262df Binary files /dev/null and b/main/assets/locales/hi-IN/activation.ogg differ diff --git a/main/assets/locales/hi-IN/err_pin.ogg b/main/assets/locales/hi-IN/err_pin.ogg new file mode 100644 index 0000000..00669fa Binary files /dev/null and b/main/assets/locales/hi-IN/err_pin.ogg differ diff --git a/main/assets/locales/hi-IN/err_reg.ogg b/main/assets/locales/hi-IN/err_reg.ogg new file mode 100644 index 0000000..6194739 Binary files /dev/null and b/main/assets/locales/hi-IN/err_reg.ogg differ diff --git a/main/assets/locales/hi-IN/language.json b/main/assets/locales/hi-IN/language.json new file mode 100644 index 0000000..732176e --- /dev/null +++ b/main/assets/locales/hi-IN/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "hi-IN" + }, + "strings": { + "WARNING": "चेतावनी", + "INFO": "जानकारी", + "ERROR": "त्रुटि", + "VERSION": "संस्करण ", + "LOADING_PROTOCOL": "सर्वर से कनेक्ट हो रहे हैं...", + "INITIALIZING": "आरंभीकरण...", + "PIN_ERROR": "कृपया सिम कार्ड डालें", + "REG_ERROR": "नेटवर्क तक पहुंच नहीं हो सकती, कृपया डेटा कार्ड स्थिति जांचें", + "DETECTING_MODULE": "मॉड्यूल का पता लगाया जा रहा है...", + "REGISTERING_NETWORK": "नेटवर्क की प्रतीक्षा...", + "CHECKING_NEW_VERSION": "नया संस्करण जाँच रहे हैं...", + "CHECK_NEW_VERSION_FAILED": "नया संस्करण जाँचना असफल, %d सेकंड में पुनः प्रयास: %s", + "SWITCH_TO_WIFI_NETWORK": "Wi-Fi पर स्विच कर रहे हैं...", + "SWITCH_TO_4G_NETWORK": "4G पर स्विच कर रहे हैं...", + "STANDBY": "स्टैंडबाय", + "CONNECT_TO": "कनेक्ट करें ", + "CONNECTING": "कनेक्ट हो रहे हैं...", + "CONNECTED_TO": "कनेक्ट हो गए ", + "LISTENING": "सुन रहे हैं...", + "SPEAKING": "बोल रहे हैं...", + "SERVER_NOT_FOUND": "उपलब्ध सेवा खोज रहे हैं", + "SERVER_NOT_CONNECTED": "सेवा से कनेक्ट नहीं हो सकते, कृपया बाद में कोशिश करें", + "SERVER_TIMEOUT": "प्रतिक्रिया का समय समाप्त", + "SERVER_ERROR": "भेजना असफल, कृपया नेटवर्क जांचें", + "CONNECT_TO_HOTSPOT": "फोन को हॉटस्पॉट से कनेक्ट करें ", + "ACCESS_VIA_BROWSER": ",ब्राउज़र के माध्यम से पहुंचें ", + "WIFI_CONFIG_MODE": "नेटवर्क कॉन्फ़िगरेशन मोड", + "ENTERING_WIFI_CONFIG_MODE": "नेटवर्क कॉन्फ़िगरेशन मोड में प्रवेश...", + "SCANNING_WIFI": "Wi-Fi स्कैन कर रहे हैं...", + "NEW_VERSION": "नया संस्करण ", + "OTA_UPGRADE": "OTA अपग्रेड", + "UPGRADING": "सिस्टम अपग्रेड हो रहा है...", + "UPGRADE_FAILED": "अपग्रेड असफल", + "ACTIVATION": "डिवाइस सक्रियण", + "BATTERY_LOW": "बैटरी कम", + "BATTERY_CHARGING": "चार्ज हो रही है", + "BATTERY_FULL": "बैटरी फुल", + "BATTERY_NEED_CHARGE": "बैटरी कम है, कृपया चार्ज करें", + "VOLUME": "आवाज़ ", + "MUTED": "म्यूट", + "MAX_VOLUME": "अधिकतम आवाज़", + "RTC_MODE_OFF": "AEC बंद", + "RTC_MODE_ON": "AEC चालू", + "DOWNLOAD_ASSETS_FAILED": "संसाधन डाउनलोड करने में विफल", + "LOADING_ASSETS": "संसाधन लोड हो रहे हैं...", + "PLEASE_WAIT": "कृपया प्रतीक्षा करें...", + "FOUND_NEW_ASSETS": "नए संसाधन मिले: %s", + "HELLO_MY_FRIEND": "नमस्ते, मेरे दोस्त!" + } +} \ No newline at end of file diff --git a/main/assets/locales/hi-IN/upgrade.ogg b/main/assets/locales/hi-IN/upgrade.ogg new file mode 100644 index 0000000..8de0693 Binary files /dev/null and b/main/assets/locales/hi-IN/upgrade.ogg differ diff --git a/main/assets/locales/hi-IN/welcome.ogg b/main/assets/locales/hi-IN/welcome.ogg new file mode 100644 index 0000000..3352a57 Binary files /dev/null and b/main/assets/locales/hi-IN/welcome.ogg differ diff --git a/main/assets/locales/hi-IN/wificonfig.ogg b/main/assets/locales/hi-IN/wificonfig.ogg new file mode 100644 index 0000000..5a9853f Binary files /dev/null and b/main/assets/locales/hi-IN/wificonfig.ogg differ diff --git a/main/assets/locales/hr-HR/0.ogg b/main/assets/locales/hr-HR/0.ogg new file mode 100644 index 0000000..5ee48d5 Binary files /dev/null and b/main/assets/locales/hr-HR/0.ogg differ diff --git a/main/assets/locales/hr-HR/1.ogg b/main/assets/locales/hr-HR/1.ogg new file mode 100644 index 0000000..13b1dbe Binary files /dev/null and b/main/assets/locales/hr-HR/1.ogg differ diff --git a/main/assets/locales/hr-HR/2.ogg b/main/assets/locales/hr-HR/2.ogg new file mode 100644 index 0000000..8a9c764 Binary files /dev/null and b/main/assets/locales/hr-HR/2.ogg differ diff --git a/main/assets/locales/hr-HR/3.ogg b/main/assets/locales/hr-HR/3.ogg new file mode 100644 index 0000000..18080eb Binary files /dev/null and b/main/assets/locales/hr-HR/3.ogg differ diff --git a/main/assets/locales/hr-HR/4.ogg b/main/assets/locales/hr-HR/4.ogg new file mode 100644 index 0000000..0f33e69 Binary files /dev/null and b/main/assets/locales/hr-HR/4.ogg differ diff --git a/main/assets/locales/hr-HR/5.ogg b/main/assets/locales/hr-HR/5.ogg new file mode 100644 index 0000000..e9bbedc Binary files /dev/null and b/main/assets/locales/hr-HR/5.ogg differ diff --git a/main/assets/locales/hr-HR/6.ogg b/main/assets/locales/hr-HR/6.ogg new file mode 100644 index 0000000..10dff31 Binary files /dev/null and b/main/assets/locales/hr-HR/6.ogg differ diff --git a/main/assets/locales/hr-HR/7.ogg b/main/assets/locales/hr-HR/7.ogg new file mode 100644 index 0000000..6e82da9 Binary files /dev/null and b/main/assets/locales/hr-HR/7.ogg differ diff --git a/main/assets/locales/hr-HR/8.ogg b/main/assets/locales/hr-HR/8.ogg new file mode 100644 index 0000000..cfac805 Binary files /dev/null and b/main/assets/locales/hr-HR/8.ogg differ diff --git a/main/assets/locales/hr-HR/9.ogg b/main/assets/locales/hr-HR/9.ogg new file mode 100644 index 0000000..ed4edfd Binary files /dev/null and b/main/assets/locales/hr-HR/9.ogg differ diff --git a/main/assets/locales/hr-HR/activation.ogg b/main/assets/locales/hr-HR/activation.ogg new file mode 100644 index 0000000..221f102 Binary files /dev/null and b/main/assets/locales/hr-HR/activation.ogg differ diff --git a/main/assets/locales/hr-HR/err_pin.ogg b/main/assets/locales/hr-HR/err_pin.ogg new file mode 100644 index 0000000..d3387bd Binary files /dev/null and b/main/assets/locales/hr-HR/err_pin.ogg differ diff --git a/main/assets/locales/hr-HR/err_reg.ogg b/main/assets/locales/hr-HR/err_reg.ogg new file mode 100644 index 0000000..a732ee9 Binary files /dev/null and b/main/assets/locales/hr-HR/err_reg.ogg differ diff --git a/main/assets/locales/hr-HR/language.json b/main/assets/locales/hr-HR/language.json new file mode 100644 index 0000000..12ce157 --- /dev/null +++ b/main/assets/locales/hr-HR/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "hr-HR" + }, + "strings": { + "WARNING": "Upozorenje", + "INFO": "Informacije", + "ERROR": "Greška", + "VERSION": "Verzija ", + "LOADING_PROTOCOL": "Prijava...", + "INITIALIZING": "Inicijalizacija...", + "PIN_ERROR": "Molimo umetnite SIM karticu", + "REG_ERROR": "Nije moguć pristup mreži, molimo provjerite status SIM kartice", + "DETECTING_MODULE": "Otkrivanje modula...", + "REGISTERING_NETWORK": "Čekanje mreže...", + "CHECKING_NEW_VERSION": "Provjera nove verzije...", + "CHECK_NEW_VERSION_FAILED": "Provjera nove verzije nije uspjela, ponovit će se za %d sekundi: %s", + "SWITCH_TO_WIFI_NETWORK": "Prebacivanje na Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Prebacivanje na 4G...", + "STANDBY": "Pripravnost", + "CONNECT_TO": "Poveži se s ", + "CONNECTING": "Povezivanje...", + "CONNECTION_SUCCESSFUL": "Uspješno povezivanje", + "CONNECTED_TO": "Povezano s ", + "LISTENING": "Slušanje...", + "SPEAKING": "Govorenje...", + "SERVER_NOT_FOUND": "Traženje dostupne usluge", + "SERVER_NOT_CONNECTED": "Nije moguće povezati se s uslugom, molimo pokušajte kasnije", + "SERVER_TIMEOUT": "Istek vremena čekanja odgovora", + "SERVER_ERROR": "Slanje nije uspjelo, molimo provjerite mrežu", + "CONNECT_TO_HOTSPOT": "Pristupna točka: ", + "ACCESS_VIA_BROWSER": " URL konfiguracije: ", + "WIFI_CONFIG_MODE": "Način konfiguracije Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Ulazak u način konfiguracije Wi-Fi...", + "SCANNING_WIFI": "Skeniranje Wi-Fi...", + "NEW_VERSION": "Nova verzija ", + "OTA_UPGRADE": "OTA nadogradnja", + "UPGRADING": "Sustav se nadograđuje...", + "UPGRADE_FAILED": "Nadogradnja nije uspjela", + "ACTIVATION": "Aktivacija", + "BATTERY_LOW": "Niska baterija", + "BATTERY_CHARGING": "Punjenje", + "BATTERY_FULL": "Baterija puna", + "BATTERY_NEED_CHARGE": "Niska baterija, molimo napunite", + "VOLUME": "Glasnoća ", + "MUTED": "Utišano", + "MAX_VOLUME": "Maksimalna glasnoća", + "RTC_MODE_OFF": "AEC isključen", + "RTC_MODE_ON": "AEC uključen", + "PLEASE_WAIT": "Molimo pričekajte...", + "FOUND_NEW_ASSETS": "Pronađeni novi resursi: %s", + "DOWNLOAD_ASSETS_FAILED": "Preuzimanje resursa nije uspjelo", + "LOADING_ASSETS": "Učitavanje resursa...", + "HELLO_MY_FRIEND": "Bok, moj prijatelju!" + } +} + diff --git a/main/assets/locales/hr-HR/upgrade.ogg b/main/assets/locales/hr-HR/upgrade.ogg new file mode 100644 index 0000000..0aa6134 Binary files /dev/null and b/main/assets/locales/hr-HR/upgrade.ogg differ diff --git a/main/assets/locales/hr-HR/welcome.ogg b/main/assets/locales/hr-HR/welcome.ogg new file mode 100644 index 0000000..8a41e8d Binary files /dev/null and b/main/assets/locales/hr-HR/welcome.ogg differ diff --git a/main/assets/locales/hr-HR/wificonfig.ogg b/main/assets/locales/hr-HR/wificonfig.ogg new file mode 100644 index 0000000..8949622 Binary files /dev/null and b/main/assets/locales/hr-HR/wificonfig.ogg differ diff --git a/main/assets/locales/hu-HU/0.ogg b/main/assets/locales/hu-HU/0.ogg new file mode 100644 index 0000000..0fabaf1 Binary files /dev/null and b/main/assets/locales/hu-HU/0.ogg differ diff --git a/main/assets/locales/hu-HU/1.ogg b/main/assets/locales/hu-HU/1.ogg new file mode 100644 index 0000000..8187037 Binary files /dev/null and b/main/assets/locales/hu-HU/1.ogg differ diff --git a/main/assets/locales/hu-HU/2.ogg b/main/assets/locales/hu-HU/2.ogg new file mode 100644 index 0000000..bf417f3 Binary files /dev/null and b/main/assets/locales/hu-HU/2.ogg differ diff --git a/main/assets/locales/hu-HU/3.ogg b/main/assets/locales/hu-HU/3.ogg new file mode 100644 index 0000000..78192eb Binary files /dev/null and b/main/assets/locales/hu-HU/3.ogg differ diff --git a/main/assets/locales/hu-HU/4.ogg b/main/assets/locales/hu-HU/4.ogg new file mode 100644 index 0000000..e93ccbf Binary files /dev/null and b/main/assets/locales/hu-HU/4.ogg differ diff --git a/main/assets/locales/hu-HU/5.ogg b/main/assets/locales/hu-HU/5.ogg new file mode 100644 index 0000000..d43909d Binary files /dev/null and b/main/assets/locales/hu-HU/5.ogg differ diff --git a/main/assets/locales/hu-HU/6.ogg b/main/assets/locales/hu-HU/6.ogg new file mode 100644 index 0000000..17344e3 Binary files /dev/null and b/main/assets/locales/hu-HU/6.ogg differ diff --git a/main/assets/locales/hu-HU/7.ogg b/main/assets/locales/hu-HU/7.ogg new file mode 100644 index 0000000..5167c43 Binary files /dev/null and b/main/assets/locales/hu-HU/7.ogg differ diff --git a/main/assets/locales/hu-HU/8.ogg b/main/assets/locales/hu-HU/8.ogg new file mode 100644 index 0000000..ba82c28 Binary files /dev/null and b/main/assets/locales/hu-HU/8.ogg differ diff --git a/main/assets/locales/hu-HU/9.ogg b/main/assets/locales/hu-HU/9.ogg new file mode 100644 index 0000000..4c1e62a Binary files /dev/null and b/main/assets/locales/hu-HU/9.ogg differ diff --git a/main/assets/locales/hu-HU/activation.ogg b/main/assets/locales/hu-HU/activation.ogg new file mode 100644 index 0000000..7e85192 Binary files /dev/null and b/main/assets/locales/hu-HU/activation.ogg differ diff --git a/main/assets/locales/hu-HU/err_pin.ogg b/main/assets/locales/hu-HU/err_pin.ogg new file mode 100644 index 0000000..fa7d637 Binary files /dev/null and b/main/assets/locales/hu-HU/err_pin.ogg differ diff --git a/main/assets/locales/hu-HU/err_reg.ogg b/main/assets/locales/hu-HU/err_reg.ogg new file mode 100644 index 0000000..d8db153 Binary files /dev/null and b/main/assets/locales/hu-HU/err_reg.ogg differ diff --git a/main/assets/locales/hu-HU/language.json b/main/assets/locales/hu-HU/language.json new file mode 100644 index 0000000..399de04 --- /dev/null +++ b/main/assets/locales/hu-HU/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "hu-HU" + }, + "strings": { + "WARNING": "Figyelmeztetés", + "INFO": "Információ", + "ERROR": "Hiba", + "VERSION": "Verzió ", + "LOADING_PROTOCOL": "Bejelentkezés...", + "INITIALIZING": "Inicializálás...", + "PIN_ERROR": "Kérjük, helyezze be a SIM kártyát", + "REG_ERROR": "A hálózat nem érhető el, kérjük, ellenőrizze a SIM kártya állapotát", + "DETECTING_MODULE": "Modul észlelése...", + "REGISTERING_NETWORK": "Várakozás a hálózatra...", + "CHECKING_NEW_VERSION": "Új verzió keresése...", + "CHECK_NEW_VERSION_FAILED": "Az új verzió keresése sikertelen, újrapróbálás %d másodperc múlva: %s", + "SWITCH_TO_WIFI_NETWORK": "Váltás Wi-Fi-re...", + "SWITCH_TO_4G_NETWORK": "Váltás 4G-re...", + "STANDBY": "Készenlét", + "CONNECT_TO": "Csatlakozás: ", + "CONNECTING": "Csatlakozás...", + "CONNECTION_SUCCESSFUL": "Sikeres csatlakozás", + "CONNECTED_TO": "Csatlakozva: ", + "LISTENING": "Figyelés...", + "SPEAKING": "Beszéd...", + "SERVER_NOT_FOUND": "Elérhető szolgáltatás keresése", + "SERVER_NOT_CONNECTED": "A szolgáltatáshoz nem sikerült csatlakozni, kérjük, próbálja újra később", + "SERVER_TIMEOUT": "A várakozási idő lejárt", + "SERVER_ERROR": "A küldés sikertelen, kérjük, ellenőrizze a hálózatot", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Konfigurációs URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi konfigurációs mód", + "ENTERING_WIFI_CONFIG_MODE": "Belépés Wi-Fi konfigurációs módba...", + "SCANNING_WIFI": "Wi-Fi keresése...", + "NEW_VERSION": "Új verzió ", + "OTA_UPGRADE": "OTA frissítés", + "UPGRADING": "A rendszer frissítése folyamatban...", + "UPGRADE_FAILED": "A frissítés sikertelen", + "ACTIVATION": "Aktiválás", + "BATTERY_LOW": "Alacsony akkumulátor", + "BATTERY_CHARGING": "Töltés", + "BATTERY_FULL": "Akkumulátor tele", + "BATTERY_NEED_CHARGE": "Alacsony akkumulátor, kérjük, töltse fel", + "VOLUME": "Hangerő ", + "MUTED": "Némítva", + "MAX_VOLUME": "Maximális hangerő", + "RTC_MODE_OFF": "AEC kikapcsolva", + "RTC_MODE_ON": "AEC bekapcsolva", + "PLEASE_WAIT": "Kérjük, várjon...", + "FOUND_NEW_ASSETS": "Új erőforrások találva: %s", + "DOWNLOAD_ASSETS_FAILED": "Az erőforrások letöltése sikertelen", + "LOADING_ASSETS": "Erőforrások betöltése...", + "HELLO_MY_FRIEND": "Helló, barátom!" + } +} + diff --git a/main/assets/locales/hu-HU/upgrade.ogg b/main/assets/locales/hu-HU/upgrade.ogg new file mode 100644 index 0000000..d894582 Binary files /dev/null and b/main/assets/locales/hu-HU/upgrade.ogg differ diff --git a/main/assets/locales/hu-HU/welcome.ogg b/main/assets/locales/hu-HU/welcome.ogg new file mode 100644 index 0000000..51d257b Binary files /dev/null and b/main/assets/locales/hu-HU/welcome.ogg differ diff --git a/main/assets/locales/hu-HU/wificonfig.ogg b/main/assets/locales/hu-HU/wificonfig.ogg new file mode 100644 index 0000000..c0e6119 Binary files /dev/null and b/main/assets/locales/hu-HU/wificonfig.ogg differ diff --git a/main/assets/locales/id-ID/0.ogg b/main/assets/locales/id-ID/0.ogg new file mode 100644 index 0000000..1d8dea3 Binary files /dev/null and b/main/assets/locales/id-ID/0.ogg differ diff --git a/main/assets/locales/id-ID/1.ogg b/main/assets/locales/id-ID/1.ogg new file mode 100644 index 0000000..cd8d7cc Binary files /dev/null and b/main/assets/locales/id-ID/1.ogg differ diff --git a/main/assets/locales/id-ID/2.ogg b/main/assets/locales/id-ID/2.ogg new file mode 100644 index 0000000..69cdce8 Binary files /dev/null and b/main/assets/locales/id-ID/2.ogg differ diff --git a/main/assets/locales/id-ID/3.ogg b/main/assets/locales/id-ID/3.ogg new file mode 100644 index 0000000..2730364 Binary files /dev/null and b/main/assets/locales/id-ID/3.ogg differ diff --git a/main/assets/locales/id-ID/4.ogg b/main/assets/locales/id-ID/4.ogg new file mode 100644 index 0000000..f26010f Binary files /dev/null and b/main/assets/locales/id-ID/4.ogg differ diff --git a/main/assets/locales/id-ID/5.ogg b/main/assets/locales/id-ID/5.ogg new file mode 100644 index 0000000..67b41f7 Binary files /dev/null and b/main/assets/locales/id-ID/5.ogg differ diff --git a/main/assets/locales/id-ID/6.ogg b/main/assets/locales/id-ID/6.ogg new file mode 100644 index 0000000..48f0343 Binary files /dev/null and b/main/assets/locales/id-ID/6.ogg differ diff --git a/main/assets/locales/id-ID/7.ogg b/main/assets/locales/id-ID/7.ogg new file mode 100644 index 0000000..c56df9f Binary files /dev/null and b/main/assets/locales/id-ID/7.ogg differ diff --git a/main/assets/locales/id-ID/8.ogg b/main/assets/locales/id-ID/8.ogg new file mode 100644 index 0000000..cb9e15b Binary files /dev/null and b/main/assets/locales/id-ID/8.ogg differ diff --git a/main/assets/locales/id-ID/9.ogg b/main/assets/locales/id-ID/9.ogg new file mode 100644 index 0000000..e088c86 Binary files /dev/null and b/main/assets/locales/id-ID/9.ogg differ diff --git a/main/assets/locales/id-ID/activation.ogg b/main/assets/locales/id-ID/activation.ogg new file mode 100644 index 0000000..a468767 Binary files /dev/null and b/main/assets/locales/id-ID/activation.ogg differ diff --git a/main/assets/locales/id-ID/err_pin.ogg b/main/assets/locales/id-ID/err_pin.ogg new file mode 100644 index 0000000..419ff8a Binary files /dev/null and b/main/assets/locales/id-ID/err_pin.ogg differ diff --git a/main/assets/locales/id-ID/err_reg.ogg b/main/assets/locales/id-ID/err_reg.ogg new file mode 100644 index 0000000..d756ddf Binary files /dev/null and b/main/assets/locales/id-ID/err_reg.ogg differ diff --git a/main/assets/locales/id-ID/language.json b/main/assets/locales/id-ID/language.json new file mode 100644 index 0000000..11224a6 --- /dev/null +++ b/main/assets/locales/id-ID/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "id-ID" + }, + "strings": { + "WARNING": "Peringatan", + "INFO": "Informasi", + "ERROR": "Kesalahan", + "VERSION": "Versi ", + "LOADING_PROTOCOL": "Menghubungkan ke server...", + "INITIALIZING": "Menginisialisasi...", + "PIN_ERROR": "Silakan masukkan kartu SIM", + "REG_ERROR": "Tidak dapat mengakses jaringan, periksa status kartu data", + "DETECTING_MODULE": "Mendeteksi modul...", + "REGISTERING_NETWORK": "Menunggu jaringan...", + "CHECKING_NEW_VERSION": "Memeriksa versi baru...", + "CHECK_NEW_VERSION_FAILED": "Pemeriksaan versi baru gagal, mencoba lagi dalam %d detik: %s", + "SWITCH_TO_WIFI_NETWORK": "Beralih ke Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Beralih ke 4G...", + "STANDBY": "Siaga", + "CONNECT_TO": "Hubungkan ke ", + "CONNECTING": "Menghubungkan...", + "CONNECTED_TO": "Terhubung ke ", + "LISTENING": "Mendengarkan...", + "SPEAKING": "Berbicara...", + "SERVER_NOT_FOUND": "Mencari layanan yang tersedia", + "SERVER_NOT_CONNECTED": "Tidak dapat terhubung ke layanan, coba lagi nanti", + "SERVER_TIMEOUT": "Waktu respons habis", + "SERVER_ERROR": "Pengiriman gagal, periksa jaringan", + "CONNECT_TO_HOTSPOT": "Hubungkan ponsel ke hotspot ", + "ACCESS_VIA_BROWSER": ",akses melalui browser ", + "WIFI_CONFIG_MODE": "Mode konfigurasi jaringan", + "ENTERING_WIFI_CONFIG_MODE": "Memasuki mode konfigurasi jaringan...", + "SCANNING_WIFI": "Memindai Wi-Fi...", + "NEW_VERSION": "Versi baru ", + "OTA_UPGRADE": "Pembaruan OTA", + "UPGRADING": "Memperbarui sistem...", + "UPGRADE_FAILED": "Pembaruan gagal", + "ACTIVATION": "Aktivasi perangkat", + "BATTERY_LOW": "Baterai lemah", + "BATTERY_CHARGING": "Mengisi", + "BATTERY_FULL": "Baterai penuh", + "BATTERY_NEED_CHARGE": "Baterai lemah, silakan isi", + "VOLUME": "Volume ", + "MUTED": "Bisu", + "MAX_VOLUME": "Volume maksimum", + "RTC_MODE_OFF": "AEC mati", + "RTC_MODE_ON": "AEC nyala", + "DOWNLOAD_ASSETS_FAILED": "Gagal mengunduh aset", + "LOADING_ASSETS": "Memuat aset...", + "PLEASE_WAIT": "Mohon tunggu...", + "FOUND_NEW_ASSETS": "Ditemukan aset baru: %s", + "HELLO_MY_FRIEND": "Halo, teman saya!" + } +} \ No newline at end of file diff --git a/main/assets/locales/id-ID/upgrade.ogg b/main/assets/locales/id-ID/upgrade.ogg new file mode 100644 index 0000000..cc2557a Binary files /dev/null and b/main/assets/locales/id-ID/upgrade.ogg differ diff --git a/main/assets/locales/id-ID/welcome.ogg b/main/assets/locales/id-ID/welcome.ogg new file mode 100644 index 0000000..57beac6 Binary files /dev/null and b/main/assets/locales/id-ID/welcome.ogg differ diff --git a/main/assets/locales/id-ID/wificonfig.ogg b/main/assets/locales/id-ID/wificonfig.ogg new file mode 100644 index 0000000..477acdd Binary files /dev/null and b/main/assets/locales/id-ID/wificonfig.ogg differ diff --git a/main/assets/locales/it-IT/0.ogg b/main/assets/locales/it-IT/0.ogg new file mode 100644 index 0000000..ae426e3 Binary files /dev/null and b/main/assets/locales/it-IT/0.ogg differ diff --git a/main/assets/locales/it-IT/1.ogg b/main/assets/locales/it-IT/1.ogg new file mode 100644 index 0000000..7c97b52 Binary files /dev/null and b/main/assets/locales/it-IT/1.ogg differ diff --git a/main/assets/locales/it-IT/2.ogg b/main/assets/locales/it-IT/2.ogg new file mode 100644 index 0000000..3d7995a Binary files /dev/null and b/main/assets/locales/it-IT/2.ogg differ diff --git a/main/assets/locales/it-IT/3.ogg b/main/assets/locales/it-IT/3.ogg new file mode 100644 index 0000000..b22ad1e Binary files /dev/null and b/main/assets/locales/it-IT/3.ogg differ diff --git a/main/assets/locales/it-IT/4.ogg b/main/assets/locales/it-IT/4.ogg new file mode 100644 index 0000000..ef01a46 Binary files /dev/null and b/main/assets/locales/it-IT/4.ogg differ diff --git a/main/assets/locales/it-IT/5.ogg b/main/assets/locales/it-IT/5.ogg new file mode 100644 index 0000000..d240b88 Binary files /dev/null and b/main/assets/locales/it-IT/5.ogg differ diff --git a/main/assets/locales/it-IT/6.ogg b/main/assets/locales/it-IT/6.ogg new file mode 100644 index 0000000..c52a2d7 Binary files /dev/null and b/main/assets/locales/it-IT/6.ogg differ diff --git a/main/assets/locales/it-IT/7.ogg b/main/assets/locales/it-IT/7.ogg new file mode 100644 index 0000000..dce632c Binary files /dev/null and b/main/assets/locales/it-IT/7.ogg differ diff --git a/main/assets/locales/it-IT/8.ogg b/main/assets/locales/it-IT/8.ogg new file mode 100644 index 0000000..acd19e8 Binary files /dev/null and b/main/assets/locales/it-IT/8.ogg differ diff --git a/main/assets/locales/it-IT/9.ogg b/main/assets/locales/it-IT/9.ogg new file mode 100644 index 0000000..807c226 Binary files /dev/null and b/main/assets/locales/it-IT/9.ogg differ diff --git a/main/assets/locales/it-IT/activation.ogg b/main/assets/locales/it-IT/activation.ogg new file mode 100644 index 0000000..6381325 Binary files /dev/null and b/main/assets/locales/it-IT/activation.ogg differ diff --git a/main/assets/locales/it-IT/err_pin.ogg b/main/assets/locales/it-IT/err_pin.ogg new file mode 100644 index 0000000..3fb7107 Binary files /dev/null and b/main/assets/locales/it-IT/err_pin.ogg differ diff --git a/main/assets/locales/it-IT/err_reg.ogg b/main/assets/locales/it-IT/err_reg.ogg new file mode 100644 index 0000000..3bbe56e Binary files /dev/null and b/main/assets/locales/it-IT/err_reg.ogg differ diff --git a/main/assets/locales/it-IT/language.json b/main/assets/locales/it-IT/language.json new file mode 100644 index 0000000..54cc9bc --- /dev/null +++ b/main/assets/locales/it-IT/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "it-IT" + }, + "strings": { + "WARNING": "Avviso", + "INFO": "Informazione", + "ERROR": "Errore", + "VERSION": "Versione ", + "LOADING_PROTOCOL": "Connessione al server...", + "INITIALIZING": "Inizializzazione...", + "PIN_ERROR": "Inserire la scheda SIM", + "REG_ERROR": "Impossibile accedere alla rete, controllare lo stato della scheda dati", + "DETECTING_MODULE": "Rilevamento modulo...", + "REGISTERING_NETWORK": "In attesa della rete...", + "CHECKING_NEW_VERSION": "Controllo nuova versione...", + "CHECK_NEW_VERSION_FAILED": "Controllo nuova versione fallito, riprovo tra %d secondi: %s", + "SWITCH_TO_WIFI_NETWORK": "Passaggio a Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Passaggio a 4G...", + "STANDBY": "In attesa", + "CONNECT_TO": "Connetti a ", + "CONNECTING": "Connessione...", + "CONNECTED_TO": "Connesso a ", + "LISTENING": "In ascolto...", + "SPEAKING": "Parlando...", + "SERVER_NOT_FOUND": "Ricerca servizio disponibile", + "SERVER_NOT_CONNECTED": "Impossibile connettersi al servizio, riprovare più tardi", + "SERVER_TIMEOUT": "Timeout risposta", + "SERVER_ERROR": "Invio fallito, controllare la rete", + "CONNECT_TO_HOTSPOT": "Connetti telefono al hotspot ", + "ACCESS_VIA_BROWSER": ",accedi tramite browser ", + "WIFI_CONFIG_MODE": "Modalità configurazione rete", + "ENTERING_WIFI_CONFIG_MODE": "Entrata in modalità configurazione rete...", + "SCANNING_WIFI": "Scansione Wi-Fi...", + "NEW_VERSION": "Nuova versione ", + "OTA_UPGRADE": "Aggiornamento OTA", + "UPGRADING": "Aggiornamento sistema...", + "UPGRADE_FAILED": "Aggiornamento fallito", + "ACTIVATION": "Attivazione dispositivo", + "BATTERY_LOW": "Batteria scarica", + "BATTERY_CHARGING": "In carica", + "BATTERY_FULL": "Batteria piena", + "BATTERY_NEED_CHARGE": "Batteria scarica, ricaricare", + "VOLUME": "Volume ", + "MUTED": "Silenziato", + "MAX_VOLUME": "Volume massimo", + "RTC_MODE_OFF": "AEC disattivato", + "RTC_MODE_ON": "AEC attivato", + "DOWNLOAD_ASSETS_FAILED": "Impossibile scaricare le risorse", + "LOADING_ASSETS": "Caricamento risorse...", + "PLEASE_WAIT": "Attendere prego...", + "FOUND_NEW_ASSETS": "Trovate nuove risorse: %s", + "HELLO_MY_FRIEND": "Ciao, amico mio!" + } +} \ No newline at end of file diff --git a/main/assets/locales/it-IT/upgrade.ogg b/main/assets/locales/it-IT/upgrade.ogg new file mode 100644 index 0000000..79c0048 Binary files /dev/null and b/main/assets/locales/it-IT/upgrade.ogg differ diff --git a/main/assets/locales/it-IT/welcome.ogg b/main/assets/locales/it-IT/welcome.ogg new file mode 100644 index 0000000..702def3 Binary files /dev/null and b/main/assets/locales/it-IT/welcome.ogg differ diff --git a/main/assets/locales/it-IT/wificonfig.ogg b/main/assets/locales/it-IT/wificonfig.ogg new file mode 100644 index 0000000..7aae624 Binary files /dev/null and b/main/assets/locales/it-IT/wificonfig.ogg differ diff --git a/main/assets/locales/ja-JP/0.ogg b/main/assets/locales/ja-JP/0.ogg new file mode 100644 index 0000000..5b24d6a Binary files /dev/null and b/main/assets/locales/ja-JP/0.ogg differ diff --git a/main/assets/locales/ja-JP/1.ogg b/main/assets/locales/ja-JP/1.ogg new file mode 100644 index 0000000..e31933d Binary files /dev/null and b/main/assets/locales/ja-JP/1.ogg differ diff --git a/main/assets/locales/ja-JP/2.ogg b/main/assets/locales/ja-JP/2.ogg new file mode 100644 index 0000000..f75a934 Binary files /dev/null and b/main/assets/locales/ja-JP/2.ogg differ diff --git a/main/assets/locales/ja-JP/3.ogg b/main/assets/locales/ja-JP/3.ogg new file mode 100644 index 0000000..e414b59 Binary files /dev/null and b/main/assets/locales/ja-JP/3.ogg differ diff --git a/main/assets/locales/ja-JP/4.ogg b/main/assets/locales/ja-JP/4.ogg new file mode 100644 index 0000000..a977c97 Binary files /dev/null and b/main/assets/locales/ja-JP/4.ogg differ diff --git a/main/assets/locales/ja-JP/5.ogg b/main/assets/locales/ja-JP/5.ogg new file mode 100644 index 0000000..52ccf1b Binary files /dev/null and b/main/assets/locales/ja-JP/5.ogg differ diff --git a/main/assets/locales/ja-JP/6.ogg b/main/assets/locales/ja-JP/6.ogg new file mode 100644 index 0000000..361f2e6 Binary files /dev/null and b/main/assets/locales/ja-JP/6.ogg differ diff --git a/main/assets/locales/ja-JP/7.ogg b/main/assets/locales/ja-JP/7.ogg new file mode 100644 index 0000000..e98be57 Binary files /dev/null and b/main/assets/locales/ja-JP/7.ogg differ diff --git a/main/assets/locales/ja-JP/8.ogg b/main/assets/locales/ja-JP/8.ogg new file mode 100644 index 0000000..2f33874 Binary files /dev/null and b/main/assets/locales/ja-JP/8.ogg differ diff --git a/main/assets/locales/ja-JP/9.ogg b/main/assets/locales/ja-JP/9.ogg new file mode 100644 index 0000000..c150a18 Binary files /dev/null and b/main/assets/locales/ja-JP/9.ogg differ diff --git a/main/assets/locales/ja-JP/activation.ogg b/main/assets/locales/ja-JP/activation.ogg new file mode 100644 index 0000000..995a489 Binary files /dev/null and b/main/assets/locales/ja-JP/activation.ogg differ diff --git a/main/assets/locales/ja-JP/err_pin.ogg b/main/assets/locales/ja-JP/err_pin.ogg new file mode 100644 index 0000000..120bd6c Binary files /dev/null and b/main/assets/locales/ja-JP/err_pin.ogg differ diff --git a/main/assets/locales/ja-JP/err_reg.ogg b/main/assets/locales/ja-JP/err_reg.ogg new file mode 100644 index 0000000..27ccc93 Binary files /dev/null and b/main/assets/locales/ja-JP/err_reg.ogg differ diff --git a/main/assets/locales/ja-JP/language.json b/main/assets/locales/ja-JP/language.json new file mode 100644 index 0000000..1c2bd82 --- /dev/null +++ b/main/assets/locales/ja-JP/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "ja-JP" + }, + "strings": { + "WARNING": "警告", + "INFO": "情報", + "ERROR": "エラー", + "VERSION": "バージョン ", + "LOADING_PROTOCOL": "サーバーにログイン中...", + "INITIALIZING": "初期化中...", + "PIN_ERROR": "SIMカードを挿入してください", + "REG_ERROR": "ネットワークに接続できません。ネットワーク状態を確認してください", + "DETECTING_MODULE": "モジュールを検出中...", + "REGISTERING_NETWORK": "ネットワーク接続待機中...", + "CHECKING_NEW_VERSION": "新しいバージョンを確認中...", + "CHECK_NEW_VERSION_FAILED": "更新確認に失敗しました。%d 秒後に再試行します: %s", + "SWITCH_TO_WIFI_NETWORK": "Wi-Fiに切り替え中...", + "SWITCH_TO_4G_NETWORK": "4Gに切り替え中...", + "STANDBY": "待機中", + "CONNECT_TO": "接続先 ", + "CONNECTING": "接続中...", + "CONNECTED_TO": "接続完了 ", + "LISTENING": "リスニング中...", + "SPEAKING": "話しています...", + "SERVER_NOT_FOUND": "利用可能なサーバーを探しています", + "SERVER_NOT_CONNECTED": "サーバーに接続できません。後でもう一度お試しください", + "SERVER_TIMEOUT": "応答待機時間が終了しました", + "SERVER_ERROR": "送信に失敗しました。ネットワークを確認してください", + "CONNECT_TO_HOTSPOT": "スマートフォンをWi-Fi ", + "ACCESS_VIA_BROWSER": " に接続し、ブラウザでアクセスしてください ", + "WIFI_CONFIG_MODE": "ネットワーク設定モード", + "ENTERING_WIFI_CONFIG_MODE": "ネットワーク設定中...", + "SCANNING_WIFI": "Wi-Fiをスキャン中...", + "NEW_VERSION": "新しいバージョン ", + "OTA_UPGRADE": "OTAアップグレード", + "UPGRADING": "システムをアップグレード中...", + "UPGRADE_FAILED": "アップグレード失敗", + "ACTIVATION": "デバイスをアクティベート", + "BATTERY_LOW": "バッテリーが少なくなっています", + "BATTERY_CHARGING": "充電中", + "BATTERY_FULL": "バッテリー満タン", + "BATTERY_NEED_CHARGE": "バッテリーが低下しています。充電してください", + "VOLUME": "音量 ", + "MUTED": "ミュートされています", + "MAX_VOLUME": "最大音量", + "RTC_MODE_OFF": "AEC 無効", + "RTC_MODE_ON": "AEC 有効", + "DOWNLOAD_ASSETS_FAILED": "アセットのダウンロードに失敗しました", + "LOADING_ASSETS": "アセットを読み込み中...", + "PLEASE_WAIT": "お待ちください...", + "FOUND_NEW_ASSETS": "新しいアセットが見つかりました: %s", + "HELLO_MY_FRIEND": "こんにちは、友達!" + } +} \ No newline at end of file diff --git a/main/assets/locales/ja-JP/upgrade.ogg b/main/assets/locales/ja-JP/upgrade.ogg new file mode 100644 index 0000000..1994026 Binary files /dev/null and b/main/assets/locales/ja-JP/upgrade.ogg differ diff --git a/main/assets/locales/ja-JP/welcome.ogg b/main/assets/locales/ja-JP/welcome.ogg new file mode 100644 index 0000000..f2a4f17 Binary files /dev/null and b/main/assets/locales/ja-JP/welcome.ogg differ diff --git a/main/assets/locales/ja-JP/wificonfig.ogg b/main/assets/locales/ja-JP/wificonfig.ogg new file mode 100644 index 0000000..16fbf94 Binary files /dev/null and b/main/assets/locales/ja-JP/wificonfig.ogg differ diff --git a/main/assets/locales/ko-KR/0.ogg b/main/assets/locales/ko-KR/0.ogg new file mode 100644 index 0000000..7c29fe5 Binary files /dev/null and b/main/assets/locales/ko-KR/0.ogg differ diff --git a/main/assets/locales/ko-KR/1.ogg b/main/assets/locales/ko-KR/1.ogg new file mode 100644 index 0000000..031d5d8 Binary files /dev/null and b/main/assets/locales/ko-KR/1.ogg differ diff --git a/main/assets/locales/ko-KR/2.ogg b/main/assets/locales/ko-KR/2.ogg new file mode 100644 index 0000000..7a12499 Binary files /dev/null and b/main/assets/locales/ko-KR/2.ogg differ diff --git a/main/assets/locales/ko-KR/3.ogg b/main/assets/locales/ko-KR/3.ogg new file mode 100644 index 0000000..c3b7a52 Binary files /dev/null and b/main/assets/locales/ko-KR/3.ogg differ diff --git a/main/assets/locales/ko-KR/4.ogg b/main/assets/locales/ko-KR/4.ogg new file mode 100644 index 0000000..79f515e Binary files /dev/null and b/main/assets/locales/ko-KR/4.ogg differ diff --git a/main/assets/locales/ko-KR/5.ogg b/main/assets/locales/ko-KR/5.ogg new file mode 100644 index 0000000..2cc2c65 Binary files /dev/null and b/main/assets/locales/ko-KR/5.ogg differ diff --git a/main/assets/locales/ko-KR/6.ogg b/main/assets/locales/ko-KR/6.ogg new file mode 100644 index 0000000..84653eb Binary files /dev/null and b/main/assets/locales/ko-KR/6.ogg differ diff --git a/main/assets/locales/ko-KR/7.ogg b/main/assets/locales/ko-KR/7.ogg new file mode 100644 index 0000000..e3e6515 Binary files /dev/null and b/main/assets/locales/ko-KR/7.ogg differ diff --git a/main/assets/locales/ko-KR/8.ogg b/main/assets/locales/ko-KR/8.ogg new file mode 100644 index 0000000..b9b7607 Binary files /dev/null and b/main/assets/locales/ko-KR/8.ogg differ diff --git a/main/assets/locales/ko-KR/9.ogg b/main/assets/locales/ko-KR/9.ogg new file mode 100644 index 0000000..9060b21 Binary files /dev/null and b/main/assets/locales/ko-KR/9.ogg differ diff --git a/main/assets/locales/ko-KR/activation.ogg b/main/assets/locales/ko-KR/activation.ogg new file mode 100644 index 0000000..1af58af Binary files /dev/null and b/main/assets/locales/ko-KR/activation.ogg differ diff --git a/main/assets/locales/ko-KR/err_pin.ogg b/main/assets/locales/ko-KR/err_pin.ogg new file mode 100644 index 0000000..508e926 Binary files /dev/null and b/main/assets/locales/ko-KR/err_pin.ogg differ diff --git a/main/assets/locales/ko-KR/err_reg.ogg b/main/assets/locales/ko-KR/err_reg.ogg new file mode 100644 index 0000000..68561fe Binary files /dev/null and b/main/assets/locales/ko-KR/err_reg.ogg differ diff --git a/main/assets/locales/ko-KR/language.json b/main/assets/locales/ko-KR/language.json new file mode 100644 index 0000000..1d65bfb --- /dev/null +++ b/main/assets/locales/ko-KR/language.json @@ -0,0 +1,56 @@ +{ + "language": { + "type": "ko-KR" + }, + "strings": { + "WARNING": "경고", + "INFO": "정보", + "ERROR": "오류", + "VERSION": "버전 ", + "LOADING_PROTOCOL": "로그인 중...", + "INITIALIZING": "초기화 중...", + "PIN_ERROR": "SIM 카드를 삽입하세요", + "REG_ERROR": "네트워크에 접속할 수 없습니다. SIM 카드 상태를 확인하세요", + "DETECTING_MODULE": "모듈 감지 중...", + "REGISTERING_NETWORK": "네트워크 대기 중...", + "CHECKING_NEW_VERSION": "새 버전 확인 중...", + "CHECK_NEW_VERSION_FAILED": "새 버전 확인에 실패했습니다. %d초 후에 다시 시도합니다: %s", + "SWITCH_TO_WIFI_NETWORK": "Wi-Fi로 전환 중...", + "SWITCH_TO_4G_NETWORK": "4G로 전환 중...", + "STANDBY": "대기", + "CONNECT_TO": "연결 대상: ", + "CONNECTING": "연결 중...", + "CONNECTION_SUCCESSFUL": "연결 성공", + "CONNECTED_TO": "연결됨: ", + "LISTENING": "듣는 중...", + "SPEAKING": "말하는 중...", + "SERVER_NOT_FOUND": "사용 가능한 서비스를 찾는 중", + "SERVER_NOT_CONNECTED": "서비스에 연결할 수 없습니다. 나중에 다시 시도하세요", + "SERVER_TIMEOUT": "응답 대기 시간 초과", + "SERVER_ERROR": "전송 실패, 네트워크를 확인하세요", + "CONNECT_TO_HOTSPOT": "핫스팟: ", + "ACCESS_VIA_BROWSER": " 설정 URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi 설정 모드", + "ENTERING_WIFI_CONFIG_MODE": "Wi-Fi 설정 모드 진입 중...", + "SCANNING_WIFI": "Wi-Fi 스캔 중...", + "NEW_VERSION": "새 버전 ", + "OTA_UPGRADE": "OTA 업그레이드", + "UPGRADING": "시스템 업그레이드 중...", + "UPGRADE_FAILED": "업그레이드 실패", + "ACTIVATION": "활성화", + "BATTERY_LOW": "배터리 부족", + "BATTERY_CHARGING": "충전 중", + "BATTERY_FULL": "배터리 완충", + "BATTERY_NEED_CHARGE": "배터리 부족, 충전하세요", + "VOLUME": "볼륨 ", + "MUTED": "음소거", + "MAX_VOLUME": "최대 볼륨", + "RTC_MODE_OFF": "AEC 끄기", + "RTC_MODE_ON": "AEC 켜기", + "DOWNLOAD_ASSETS_FAILED": "에셋 다운로드 실패", + "LOADING_ASSETS": "에셋 로딩 중...", + "PLEASE_WAIT": "잠시 기다려 주세요...", + "FOUND_NEW_ASSETS": "새로운 에셋을 발견했습니다: %s", + "HELLO_MY_FRIEND": "안녕하세요, 친구!" + } +} \ No newline at end of file diff --git a/main/assets/locales/ko-KR/upgrade.ogg b/main/assets/locales/ko-KR/upgrade.ogg new file mode 100644 index 0000000..0656a78 Binary files /dev/null and b/main/assets/locales/ko-KR/upgrade.ogg differ diff --git a/main/assets/locales/ko-KR/welcome.ogg b/main/assets/locales/ko-KR/welcome.ogg new file mode 100644 index 0000000..59621f4 Binary files /dev/null and b/main/assets/locales/ko-KR/welcome.ogg differ diff --git a/main/assets/locales/ko-KR/wificonfig.ogg b/main/assets/locales/ko-KR/wificonfig.ogg new file mode 100644 index 0000000..e1610af Binary files /dev/null and b/main/assets/locales/ko-KR/wificonfig.ogg differ diff --git a/main/assets/locales/ms-MY/0.ogg b/main/assets/locales/ms-MY/0.ogg new file mode 100644 index 0000000..2a6fc02 Binary files /dev/null and b/main/assets/locales/ms-MY/0.ogg differ diff --git a/main/assets/locales/ms-MY/1.ogg b/main/assets/locales/ms-MY/1.ogg new file mode 100644 index 0000000..01103be Binary files /dev/null and b/main/assets/locales/ms-MY/1.ogg differ diff --git a/main/assets/locales/ms-MY/2.ogg b/main/assets/locales/ms-MY/2.ogg new file mode 100644 index 0000000..52e8ac6 Binary files /dev/null and b/main/assets/locales/ms-MY/2.ogg differ diff --git a/main/assets/locales/ms-MY/3.ogg b/main/assets/locales/ms-MY/3.ogg new file mode 100644 index 0000000..16e3d76 Binary files /dev/null and b/main/assets/locales/ms-MY/3.ogg differ diff --git a/main/assets/locales/ms-MY/4.ogg b/main/assets/locales/ms-MY/4.ogg new file mode 100644 index 0000000..3a3ec0a Binary files /dev/null and b/main/assets/locales/ms-MY/4.ogg differ diff --git a/main/assets/locales/ms-MY/5.ogg b/main/assets/locales/ms-MY/5.ogg new file mode 100644 index 0000000..3dd6c06 Binary files /dev/null and b/main/assets/locales/ms-MY/5.ogg differ diff --git a/main/assets/locales/ms-MY/6.ogg b/main/assets/locales/ms-MY/6.ogg new file mode 100644 index 0000000..a8e3aed Binary files /dev/null and b/main/assets/locales/ms-MY/6.ogg differ diff --git a/main/assets/locales/ms-MY/7.ogg b/main/assets/locales/ms-MY/7.ogg new file mode 100644 index 0000000..d2fc950 Binary files /dev/null and b/main/assets/locales/ms-MY/7.ogg differ diff --git a/main/assets/locales/ms-MY/8.ogg b/main/assets/locales/ms-MY/8.ogg new file mode 100644 index 0000000..20e94da Binary files /dev/null and b/main/assets/locales/ms-MY/8.ogg differ diff --git a/main/assets/locales/ms-MY/9.ogg b/main/assets/locales/ms-MY/9.ogg new file mode 100644 index 0000000..61f7b96 Binary files /dev/null and b/main/assets/locales/ms-MY/9.ogg differ diff --git a/main/assets/locales/ms-MY/activation.ogg b/main/assets/locales/ms-MY/activation.ogg new file mode 100644 index 0000000..8fea3ae Binary files /dev/null and b/main/assets/locales/ms-MY/activation.ogg differ diff --git a/main/assets/locales/ms-MY/err_pin.ogg b/main/assets/locales/ms-MY/err_pin.ogg new file mode 100644 index 0000000..8221763 Binary files /dev/null and b/main/assets/locales/ms-MY/err_pin.ogg differ diff --git a/main/assets/locales/ms-MY/err_reg.ogg b/main/assets/locales/ms-MY/err_reg.ogg new file mode 100644 index 0000000..51547b6 Binary files /dev/null and b/main/assets/locales/ms-MY/err_reg.ogg differ diff --git a/main/assets/locales/ms-MY/language.json b/main/assets/locales/ms-MY/language.json new file mode 100644 index 0000000..5a6fc0b --- /dev/null +++ b/main/assets/locales/ms-MY/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "ms-MY" + }, + "strings": { + "WARNING": "Amaran", + "INFO": "Maklumat", + "ERROR": "Ralat", + "VERSION": "Versi ", + "LOADING_PROTOCOL": "Log masuk...", + "INITIALIZING": "Memulakan...", + "PIN_ERROR": "Sila masukkan kad SIM", + "REG_ERROR": "Tidak dapat mengakses rangkaian, sila semak status kad SIM", + "DETECTING_MODULE": "Mengesan modul...", + "REGISTERING_NETWORK": "Menunggu rangkaian...", + "CHECKING_NEW_VERSION": "Memeriksa versi baharu...", + "CHECK_NEW_VERSION_FAILED": "Pemeriksaan versi baharu gagal, akan cuba semula dalam %d saat: %s", + "SWITCH_TO_WIFI_NETWORK": "Bertukar ke Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Bertukar ke 4G...", + "STANDBY": "Bersedia", + "CONNECT_TO": "Sambung ke ", + "CONNECTING": "Menyambung...", + "CONNECTION_SUCCESSFUL": "Sambungan berjaya", + "CONNECTED_TO": "Disambungkan ke ", + "LISTENING": "Mendengar...", + "SPEAKING": "Bercakap...", + "SERVER_NOT_FOUND": "Mencari perkhidmatan yang tersedia", + "SERVER_NOT_CONNECTED": "Tidak dapat menyambung ke perkhidmatan, sila cuba lagi kemudian", + "SERVER_TIMEOUT": "Masa tamat menunggu respons", + "SERVER_ERROR": "Penghantaran gagal, sila semak rangkaian", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " URL konfigurasi: ", + "WIFI_CONFIG_MODE": "Mod Konfigurasi Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Memasuki mod konfigurasi Wi-Fi...", + "SCANNING_WIFI": "Mengimbas Wi-Fi...", + "NEW_VERSION": "Versi baharu ", + "OTA_UPGRADE": "Peningkatan OTA", + "UPGRADING": "Sistem sedang dinaik taraf...", + "UPGRADE_FAILED": "Peningkatan gagal", + "ACTIVATION": "Pengaktifan", + "BATTERY_LOW": "Bateri lemah", + "BATTERY_CHARGING": "Mengecas", + "BATTERY_FULL": "Bateri penuh", + "BATTERY_NEED_CHARGE": "Bateri lemah, sila cas", + "VOLUME": "Kelantangan ", + "MUTED": "Dibisukan", + "MAX_VOLUME": "Kelantangan maksimum", + "RTC_MODE_OFF": "AEC Dimatikan", + "RTC_MODE_ON": "AEC Dihidupkan", + "PLEASE_WAIT": "Sila tunggu...", + "FOUND_NEW_ASSETS": "Menemui aset baharu: %s", + "DOWNLOAD_ASSETS_FAILED": "Gagal memuat turun aset", + "LOADING_ASSETS": "Memuatkan aset...", + "HELLO_MY_FRIEND": "Hai, kawan saya!" + } +} + diff --git a/main/assets/locales/ms-MY/upgrade.ogg b/main/assets/locales/ms-MY/upgrade.ogg new file mode 100644 index 0000000..0bfcdcc Binary files /dev/null and b/main/assets/locales/ms-MY/upgrade.ogg differ diff --git a/main/assets/locales/ms-MY/welcome.ogg b/main/assets/locales/ms-MY/welcome.ogg new file mode 100644 index 0000000..7cd32e0 Binary files /dev/null and b/main/assets/locales/ms-MY/welcome.ogg differ diff --git a/main/assets/locales/ms-MY/wificonfig.ogg b/main/assets/locales/ms-MY/wificonfig.ogg new file mode 100644 index 0000000..a257b1d Binary files /dev/null and b/main/assets/locales/ms-MY/wificonfig.ogg differ diff --git a/main/assets/locales/nb-NO/0.ogg b/main/assets/locales/nb-NO/0.ogg new file mode 100644 index 0000000..cc14677 Binary files /dev/null and b/main/assets/locales/nb-NO/0.ogg differ diff --git a/main/assets/locales/nb-NO/1.ogg b/main/assets/locales/nb-NO/1.ogg new file mode 100644 index 0000000..1d32c29 Binary files /dev/null and b/main/assets/locales/nb-NO/1.ogg differ diff --git a/main/assets/locales/nb-NO/2.ogg b/main/assets/locales/nb-NO/2.ogg new file mode 100644 index 0000000..00d3536 Binary files /dev/null and b/main/assets/locales/nb-NO/2.ogg differ diff --git a/main/assets/locales/nb-NO/3.ogg b/main/assets/locales/nb-NO/3.ogg new file mode 100644 index 0000000..d8d4711 Binary files /dev/null and b/main/assets/locales/nb-NO/3.ogg differ diff --git a/main/assets/locales/nb-NO/4.ogg b/main/assets/locales/nb-NO/4.ogg new file mode 100644 index 0000000..eafc4ea Binary files /dev/null and b/main/assets/locales/nb-NO/4.ogg differ diff --git a/main/assets/locales/nb-NO/5.ogg b/main/assets/locales/nb-NO/5.ogg new file mode 100644 index 0000000..61d36bc Binary files /dev/null and b/main/assets/locales/nb-NO/5.ogg differ diff --git a/main/assets/locales/nb-NO/6.ogg b/main/assets/locales/nb-NO/6.ogg new file mode 100644 index 0000000..cfa848e Binary files /dev/null and b/main/assets/locales/nb-NO/6.ogg differ diff --git a/main/assets/locales/nb-NO/7.ogg b/main/assets/locales/nb-NO/7.ogg new file mode 100644 index 0000000..9391485 Binary files /dev/null and b/main/assets/locales/nb-NO/7.ogg differ diff --git a/main/assets/locales/nb-NO/8.ogg b/main/assets/locales/nb-NO/8.ogg new file mode 100644 index 0000000..946b7ac Binary files /dev/null and b/main/assets/locales/nb-NO/8.ogg differ diff --git a/main/assets/locales/nb-NO/9.ogg b/main/assets/locales/nb-NO/9.ogg new file mode 100644 index 0000000..8311b58 Binary files /dev/null and b/main/assets/locales/nb-NO/9.ogg differ diff --git a/main/assets/locales/nb-NO/activation.ogg b/main/assets/locales/nb-NO/activation.ogg new file mode 100644 index 0000000..8d7be02 Binary files /dev/null and b/main/assets/locales/nb-NO/activation.ogg differ diff --git a/main/assets/locales/nb-NO/err_pin.ogg b/main/assets/locales/nb-NO/err_pin.ogg new file mode 100644 index 0000000..1b6c81c Binary files /dev/null and b/main/assets/locales/nb-NO/err_pin.ogg differ diff --git a/main/assets/locales/nb-NO/err_reg.ogg b/main/assets/locales/nb-NO/err_reg.ogg new file mode 100644 index 0000000..c505fff Binary files /dev/null and b/main/assets/locales/nb-NO/err_reg.ogg differ diff --git a/main/assets/locales/nb-NO/language.json b/main/assets/locales/nb-NO/language.json new file mode 100644 index 0000000..71b0a57 --- /dev/null +++ b/main/assets/locales/nb-NO/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "nb-NO" + }, + "strings": { + "WARNING": "Advarsel", + "INFO": "Informasjon", + "ERROR": "Feil", + "VERSION": "Versjon ", + "LOADING_PROTOCOL": "Logger inn...", + "INITIALIZING": "Initialiserer...", + "PIN_ERROR": "Vennligst sett inn SIM-kort", + "REG_ERROR": "Kan ikke få tilgang til nettverket, vennligst sjekk SIM-kortets status", + "DETECTING_MODULE": "Oppdager modul...", + "REGISTERING_NETWORK": "Venter på nettverk...", + "CHECKING_NEW_VERSION": "Sjekker for ny versjon...", + "CHECK_NEW_VERSION_FAILED": "Sjekk for ny versjon mislyktes, prøver på nytt om %d sekunder: %s", + "SWITCH_TO_WIFI_NETWORK": "Bytter til Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Bytter til 4G...", + "STANDBY": "Standby", + "CONNECT_TO": "Koble til ", + "CONNECTING": "Kobler til...", + "CONNECTION_SUCCESSFUL": "Tilkobling vellykket", + "CONNECTED_TO": "Koblet til ", + "LISTENING": "Lytter...", + "SPEAKING": "Snakker...", + "SERVER_NOT_FOUND": "Søker etter tilgjengelig tjeneste", + "SERVER_NOT_CONNECTED": "Kan ikke koble til tjeneste, vennligst prøv igjen senere", + "SERVER_TIMEOUT": "Tidsavbrudd for å vente på svar", + "SERVER_ERROR": "Sending mislyktes, vennligst sjekk nettverket", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Konfigurasjon-URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi konfigurasjonsmodus", + "ENTERING_WIFI_CONFIG_MODE": "Går inn i Wi-Fi konfigurasjonsmodus...", + "SCANNING_WIFI": "Skanner Wi-Fi...", + "NEW_VERSION": "Ny versjon ", + "OTA_UPGRADE": "OTA-oppgradering", + "UPGRADING": "Systemet oppgraderes...", + "UPGRADE_FAILED": "Oppgradering mislyktes", + "ACTIVATION": "Aktivering", + "BATTERY_LOW": "Lavt batteri", + "BATTERY_CHARGING": "Lader", + "BATTERY_FULL": "Batteriet er fullt", + "BATTERY_NEED_CHARGE": "Lavt batteri, vennligst lad", + "VOLUME": "Volum ", + "MUTED": "Dempet", + "MAX_VOLUME": "Maksimalt volum", + "RTC_MODE_OFF": "AEC av", + "RTC_MODE_ON": "AEC på", + "PLEASE_WAIT": "Vennligst vent...", + "FOUND_NEW_ASSETS": "Fant nye ressurser: %s", + "DOWNLOAD_ASSETS_FAILED": "Nedlasting av ressurser mislyktes", + "LOADING_ASSETS": "Laster ressurser...", + "HELLO_MY_FRIEND": "Hei, min venn!" + } +} + diff --git a/main/assets/locales/nb-NO/upgrade.ogg b/main/assets/locales/nb-NO/upgrade.ogg new file mode 100644 index 0000000..dc914d5 Binary files /dev/null and b/main/assets/locales/nb-NO/upgrade.ogg differ diff --git a/main/assets/locales/nb-NO/welcome.ogg b/main/assets/locales/nb-NO/welcome.ogg new file mode 100644 index 0000000..0e25dc9 Binary files /dev/null and b/main/assets/locales/nb-NO/welcome.ogg differ diff --git a/main/assets/locales/nb-NO/wificonfig.ogg b/main/assets/locales/nb-NO/wificonfig.ogg new file mode 100644 index 0000000..2d0b4a4 Binary files /dev/null and b/main/assets/locales/nb-NO/wificonfig.ogg differ diff --git a/main/assets/locales/nl-NL/0.ogg b/main/assets/locales/nl-NL/0.ogg new file mode 100644 index 0000000..aba888e Binary files /dev/null and b/main/assets/locales/nl-NL/0.ogg differ diff --git a/main/assets/locales/nl-NL/1.ogg b/main/assets/locales/nl-NL/1.ogg new file mode 100644 index 0000000..31b8273 Binary files /dev/null and b/main/assets/locales/nl-NL/1.ogg differ diff --git a/main/assets/locales/nl-NL/2.ogg b/main/assets/locales/nl-NL/2.ogg new file mode 100644 index 0000000..a4e5457 Binary files /dev/null and b/main/assets/locales/nl-NL/2.ogg differ diff --git a/main/assets/locales/nl-NL/3.ogg b/main/assets/locales/nl-NL/3.ogg new file mode 100644 index 0000000..95a59cd Binary files /dev/null and b/main/assets/locales/nl-NL/3.ogg differ diff --git a/main/assets/locales/nl-NL/4.ogg b/main/assets/locales/nl-NL/4.ogg new file mode 100644 index 0000000..8d21287 Binary files /dev/null and b/main/assets/locales/nl-NL/4.ogg differ diff --git a/main/assets/locales/nl-NL/5.ogg b/main/assets/locales/nl-NL/5.ogg new file mode 100644 index 0000000..307fbfb Binary files /dev/null and b/main/assets/locales/nl-NL/5.ogg differ diff --git a/main/assets/locales/nl-NL/6.ogg b/main/assets/locales/nl-NL/6.ogg new file mode 100644 index 0000000..f03555b Binary files /dev/null and b/main/assets/locales/nl-NL/6.ogg differ diff --git a/main/assets/locales/nl-NL/7.ogg b/main/assets/locales/nl-NL/7.ogg new file mode 100644 index 0000000..759a596 Binary files /dev/null and b/main/assets/locales/nl-NL/7.ogg differ diff --git a/main/assets/locales/nl-NL/8.ogg b/main/assets/locales/nl-NL/8.ogg new file mode 100644 index 0000000..3d4183a Binary files /dev/null and b/main/assets/locales/nl-NL/8.ogg differ diff --git a/main/assets/locales/nl-NL/9.ogg b/main/assets/locales/nl-NL/9.ogg new file mode 100644 index 0000000..af53ac4 Binary files /dev/null and b/main/assets/locales/nl-NL/9.ogg differ diff --git a/main/assets/locales/nl-NL/activation.ogg b/main/assets/locales/nl-NL/activation.ogg new file mode 100644 index 0000000..273d65a Binary files /dev/null and b/main/assets/locales/nl-NL/activation.ogg differ diff --git a/main/assets/locales/nl-NL/err_pin.ogg b/main/assets/locales/nl-NL/err_pin.ogg new file mode 100644 index 0000000..a2f83c4 Binary files /dev/null and b/main/assets/locales/nl-NL/err_pin.ogg differ diff --git a/main/assets/locales/nl-NL/err_reg.ogg b/main/assets/locales/nl-NL/err_reg.ogg new file mode 100644 index 0000000..1f61dfd Binary files /dev/null and b/main/assets/locales/nl-NL/err_reg.ogg differ diff --git a/main/assets/locales/nl-NL/language.json b/main/assets/locales/nl-NL/language.json new file mode 100644 index 0000000..2c1a360 --- /dev/null +++ b/main/assets/locales/nl-NL/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "nl-NL" + }, + "strings": { + "WARNING": "Waarschuwing", + "INFO": "Informatie", + "ERROR": "Fout", + "VERSION": "Versie ", + "LOADING_PROTOCOL": "Inloggen...", + "INITIALIZING": "Initialiseren...", + "PIN_ERROR": "Plaats een SIM-kaart", + "REG_ERROR": "Geen toegang tot netwerk, controleer de SIM-kaartstatus", + "DETECTING_MODULE": "Module detecteren...", + "REGISTERING_NETWORK": "Wachten op netwerk...", + "CHECKING_NEW_VERSION": "Controleren op nieuwe versie...", + "CHECK_NEW_VERSION_FAILED": "Controle op nieuwe versie mislukt, opnieuw proberen over %d seconden: %s", + "SWITCH_TO_WIFI_NETWORK": "Overschakelen naar Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Overschakelen naar 4G...", + "STANDBY": "Stand-by", + "CONNECT_TO": "Verbinden met ", + "CONNECTING": "Verbinden...", + "CONNECTION_SUCCESSFUL": "Verbinding geslaagd", + "CONNECTED_TO": "Verbonden met ", + "LISTENING": "Luisteren...", + "SPEAKING": "Spreken...", + "SERVER_NOT_FOUND": "Zoeken naar beschikbare service", + "SERVER_NOT_CONNECTED": "Kan niet verbinden met service, probeer later opnieuw", + "SERVER_TIMEOUT": "Timeout bij wachten op reactie", + "SERVER_ERROR": "Verzenden mislukt, controleer het netwerk", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Configuratie-URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi-configuratiemodus", + "ENTERING_WIFI_CONFIG_MODE": "Wi-Fi-configuratiemodus openen...", + "SCANNING_WIFI": "Wi-Fi scannen...", + "NEW_VERSION": "Nieuwe versie ", + "OTA_UPGRADE": "OTA-upgrade", + "UPGRADING": "Systeem wordt geüpgraded...", + "UPGRADE_FAILED": "Upgrade mislukt", + "ACTIVATION": "Activering", + "BATTERY_LOW": "Batterij bijna leeg", + "BATTERY_CHARGING": "Opladen", + "BATTERY_FULL": "Batterij vol", + "BATTERY_NEED_CHARGE": "Batterij bijna leeg, laad op", + "VOLUME": "Volume ", + "MUTED": "Gedempt", + "MAX_VOLUME": "Maximaal volume", + "RTC_MODE_OFF": "AEC uit", + "RTC_MODE_ON": "AEC aan", + "PLEASE_WAIT": "Een ogenblik geduld...", + "FOUND_NEW_ASSETS": "Nieuwe bronnen gevonden: %s", + "DOWNLOAD_ASSETS_FAILED": "Downloaden van bronnen mislukt", + "LOADING_ASSETS": "Bronnen laden...", + "HELLO_MY_FRIEND": "Hallo, mijn vriend!" + } +} + diff --git a/main/assets/locales/nl-NL/upgrade.ogg b/main/assets/locales/nl-NL/upgrade.ogg new file mode 100644 index 0000000..8879792 Binary files /dev/null and b/main/assets/locales/nl-NL/upgrade.ogg differ diff --git a/main/assets/locales/nl-NL/welcome.ogg b/main/assets/locales/nl-NL/welcome.ogg new file mode 100644 index 0000000..6fcc6dd Binary files /dev/null and b/main/assets/locales/nl-NL/welcome.ogg differ diff --git a/main/assets/locales/nl-NL/wificonfig.ogg b/main/assets/locales/nl-NL/wificonfig.ogg new file mode 100644 index 0000000..ada5f98 Binary files /dev/null and b/main/assets/locales/nl-NL/wificonfig.ogg differ diff --git a/main/assets/locales/pl-PL/0.ogg b/main/assets/locales/pl-PL/0.ogg new file mode 100644 index 0000000..7351d96 Binary files /dev/null and b/main/assets/locales/pl-PL/0.ogg differ diff --git a/main/assets/locales/pl-PL/1.ogg b/main/assets/locales/pl-PL/1.ogg new file mode 100644 index 0000000..342c9cc Binary files /dev/null and b/main/assets/locales/pl-PL/1.ogg differ diff --git a/main/assets/locales/pl-PL/2.ogg b/main/assets/locales/pl-PL/2.ogg new file mode 100644 index 0000000..8fa7c87 Binary files /dev/null and b/main/assets/locales/pl-PL/2.ogg differ diff --git a/main/assets/locales/pl-PL/3.ogg b/main/assets/locales/pl-PL/3.ogg new file mode 100644 index 0000000..b656411 Binary files /dev/null and b/main/assets/locales/pl-PL/3.ogg differ diff --git a/main/assets/locales/pl-PL/4.ogg b/main/assets/locales/pl-PL/4.ogg new file mode 100644 index 0000000..ea49088 Binary files /dev/null and b/main/assets/locales/pl-PL/4.ogg differ diff --git a/main/assets/locales/pl-PL/5.ogg b/main/assets/locales/pl-PL/5.ogg new file mode 100644 index 0000000..8d4b3b9 Binary files /dev/null and b/main/assets/locales/pl-PL/5.ogg differ diff --git a/main/assets/locales/pl-PL/6.ogg b/main/assets/locales/pl-PL/6.ogg new file mode 100644 index 0000000..7c8fefd Binary files /dev/null and b/main/assets/locales/pl-PL/6.ogg differ diff --git a/main/assets/locales/pl-PL/7.ogg b/main/assets/locales/pl-PL/7.ogg new file mode 100644 index 0000000..7139591 Binary files /dev/null and b/main/assets/locales/pl-PL/7.ogg differ diff --git a/main/assets/locales/pl-PL/8.ogg b/main/assets/locales/pl-PL/8.ogg new file mode 100644 index 0000000..8e2dd56 Binary files /dev/null and b/main/assets/locales/pl-PL/8.ogg differ diff --git a/main/assets/locales/pl-PL/9.ogg b/main/assets/locales/pl-PL/9.ogg new file mode 100644 index 0000000..b88ab87 Binary files /dev/null and b/main/assets/locales/pl-PL/9.ogg differ diff --git a/main/assets/locales/pl-PL/activation.ogg b/main/assets/locales/pl-PL/activation.ogg new file mode 100644 index 0000000..7c1ff9d Binary files /dev/null and b/main/assets/locales/pl-PL/activation.ogg differ diff --git a/main/assets/locales/pl-PL/err_pin.ogg b/main/assets/locales/pl-PL/err_pin.ogg new file mode 100644 index 0000000..4d35f3c Binary files /dev/null and b/main/assets/locales/pl-PL/err_pin.ogg differ diff --git a/main/assets/locales/pl-PL/err_reg.ogg b/main/assets/locales/pl-PL/err_reg.ogg new file mode 100644 index 0000000..35d1452 Binary files /dev/null and b/main/assets/locales/pl-PL/err_reg.ogg differ diff --git a/main/assets/locales/pl-PL/language.json b/main/assets/locales/pl-PL/language.json new file mode 100644 index 0000000..b54c292 --- /dev/null +++ b/main/assets/locales/pl-PL/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "pl-PL" + }, + "strings": { + "WARNING": "Ostrzeżenie", + "INFO": "Informacja", + "ERROR": "Błąd", + "VERSION": "Wersja ", + "LOADING_PROTOCOL": "Łączenie z serwerem...", + "INITIALIZING": "Inicjalizacja...", + "PIN_ERROR": "Proszę włożyć kartę SIM", + "REG_ERROR": "Nie można uzyskać dostępu do sieci, sprawdź stan karty danych", + "DETECTING_MODULE": "Wykrywanie modułu...", + "REGISTERING_NETWORK": "Oczekiwanie na sieć...", + "CHECKING_NEW_VERSION": "Sprawdzanie nowej wersji...", + "CHECK_NEW_VERSION_FAILED": "Sprawdzanie nowej wersji nie powiodło się, ponowna próba za %d sekund: %s", + "SWITCH_TO_WIFI_NETWORK": "Przełączanie na Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Przełączanie na 4G...", + "STANDBY": "Gotowość", + "CONNECT_TO": "Połącz z ", + "CONNECTING": "Łączenie...", + "CONNECTED_TO": "Połączono z ", + "LISTENING": "Słuchanie...", + "SPEAKING": "Mówienie...", + "SERVER_NOT_FOUND": "Szukanie dostępnej usługi", + "SERVER_NOT_CONNECTED": "Nie można połączyć się z usługą, spróbuj ponownie później", + "SERVER_TIMEOUT": "Przekroczono czas oczekiwania na odpowiedź", + "SERVER_ERROR": "Wysyłanie nie powiodło się, sprawdź sieć", + "CONNECT_TO_HOTSPOT": "Podłącz telefon do hotspotu ", + "ACCESS_VIA_BROWSER": ",dostęp przez przeglądarkę ", + "WIFI_CONFIG_MODE": "Tryb konfiguracji sieci", + "ENTERING_WIFI_CONFIG_MODE": "Wchodzenie w tryb konfiguracji sieci...", + "SCANNING_WIFI": "Skanowanie Wi-Fi...", + "NEW_VERSION": "Nowa wersja ", + "OTA_UPGRADE": "Aktualizacja OTA", + "UPGRADING": "Aktualizacja systemu...", + "UPGRADE_FAILED": "Aktualizacja nie powiodła się", + "ACTIVATION": "Aktywacja urządzenia", + "BATTERY_LOW": "Niski poziom baterii", + "BATTERY_CHARGING": "Ładowanie", + "BATTERY_FULL": "Bateria pełna", + "BATTERY_NEED_CHARGE": "Niski poziom baterii, proszę naładować", + "VOLUME": "Głośność ", + "MUTED": "Wyciszony", + "MAX_VOLUME": "Maksymalna głośność", + "RTC_MODE_OFF": "AEC wyłączony", + "RTC_MODE_ON": "AEC włączony", + "DOWNLOAD_ASSETS_FAILED": "Nie udało się pobrać zasobów", + "LOADING_ASSETS": "Ładowanie zasobów...", + "PLEASE_WAIT": "Proszę czekać...", + "FOUND_NEW_ASSETS": "Znaleziono nowe zasoby: %s", + "HELLO_MY_FRIEND": "Cześć, mój przyjacielu!" + } +} \ No newline at end of file diff --git a/main/assets/locales/pl-PL/upgrade.ogg b/main/assets/locales/pl-PL/upgrade.ogg new file mode 100644 index 0000000..041eee8 Binary files /dev/null and b/main/assets/locales/pl-PL/upgrade.ogg differ diff --git a/main/assets/locales/pl-PL/welcome.ogg b/main/assets/locales/pl-PL/welcome.ogg new file mode 100644 index 0000000..140db7d Binary files /dev/null and b/main/assets/locales/pl-PL/welcome.ogg differ diff --git a/main/assets/locales/pl-PL/wificonfig.ogg b/main/assets/locales/pl-PL/wificonfig.ogg new file mode 100644 index 0000000..0d2222f Binary files /dev/null and b/main/assets/locales/pl-PL/wificonfig.ogg differ diff --git a/main/assets/locales/pt-PT/0.ogg b/main/assets/locales/pt-PT/0.ogg new file mode 100644 index 0000000..80c9f8b Binary files /dev/null and b/main/assets/locales/pt-PT/0.ogg differ diff --git a/main/assets/locales/pt-PT/1.ogg b/main/assets/locales/pt-PT/1.ogg new file mode 100644 index 0000000..4299bc8 Binary files /dev/null and b/main/assets/locales/pt-PT/1.ogg differ diff --git a/main/assets/locales/pt-PT/2.ogg b/main/assets/locales/pt-PT/2.ogg new file mode 100644 index 0000000..fa67197 Binary files /dev/null and b/main/assets/locales/pt-PT/2.ogg differ diff --git a/main/assets/locales/pt-PT/3.ogg b/main/assets/locales/pt-PT/3.ogg new file mode 100644 index 0000000..da2b131 Binary files /dev/null and b/main/assets/locales/pt-PT/3.ogg differ diff --git a/main/assets/locales/pt-PT/4.ogg b/main/assets/locales/pt-PT/4.ogg new file mode 100644 index 0000000..2c593f6 Binary files /dev/null and b/main/assets/locales/pt-PT/4.ogg differ diff --git a/main/assets/locales/pt-PT/5.ogg b/main/assets/locales/pt-PT/5.ogg new file mode 100644 index 0000000..62d670d Binary files /dev/null and b/main/assets/locales/pt-PT/5.ogg differ diff --git a/main/assets/locales/pt-PT/6.ogg b/main/assets/locales/pt-PT/6.ogg new file mode 100644 index 0000000..32ea27b Binary files /dev/null and b/main/assets/locales/pt-PT/6.ogg differ diff --git a/main/assets/locales/pt-PT/7.ogg b/main/assets/locales/pt-PT/7.ogg new file mode 100644 index 0000000..c8542ed Binary files /dev/null and b/main/assets/locales/pt-PT/7.ogg differ diff --git a/main/assets/locales/pt-PT/8.ogg b/main/assets/locales/pt-PT/8.ogg new file mode 100644 index 0000000..8e54738 Binary files /dev/null and b/main/assets/locales/pt-PT/8.ogg differ diff --git a/main/assets/locales/pt-PT/9.ogg b/main/assets/locales/pt-PT/9.ogg new file mode 100644 index 0000000..e97c8fc Binary files /dev/null and b/main/assets/locales/pt-PT/9.ogg differ diff --git a/main/assets/locales/pt-PT/activation.ogg b/main/assets/locales/pt-PT/activation.ogg new file mode 100644 index 0000000..1c980ac Binary files /dev/null and b/main/assets/locales/pt-PT/activation.ogg differ diff --git a/main/assets/locales/pt-PT/err_pin.ogg b/main/assets/locales/pt-PT/err_pin.ogg new file mode 100644 index 0000000..ceb2223 Binary files /dev/null and b/main/assets/locales/pt-PT/err_pin.ogg differ diff --git a/main/assets/locales/pt-PT/err_reg.ogg b/main/assets/locales/pt-PT/err_reg.ogg new file mode 100644 index 0000000..2fa4350 Binary files /dev/null and b/main/assets/locales/pt-PT/err_reg.ogg differ diff --git a/main/assets/locales/pt-PT/language.json b/main/assets/locales/pt-PT/language.json new file mode 100644 index 0000000..da0e0e2 --- /dev/null +++ b/main/assets/locales/pt-PT/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "pt-PT" + }, + "strings": { + "WARNING": "Aviso", + "INFO": "Informação", + "ERROR": "Erro", + "VERSION": "Versão ", + "LOADING_PROTOCOL": "Ligando ao servidor...", + "INITIALIZING": "A inicializar...", + "PIN_ERROR": "Por favor insira o cartão SIM", + "REG_ERROR": "Não é possível aceder à rede, verifique o estado do cartão de dados", + "DETECTING_MODULE": "A detectar módulo...", + "REGISTERING_NETWORK": "À espera da rede...", + "CHECKING_NEW_VERSION": "A verificar nova versão...", + "CHECK_NEW_VERSION_FAILED": "Falha na verificação de nova versão, nova tentativa em %d segundos: %s", + "SWITCH_TO_WIFI_NETWORK": "A mudar para Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "A mudar para 4G...", + "STANDBY": "Em espera", + "CONNECT_TO": "Ligar a ", + "CONNECTING": "A ligar...", + "CONNECTED_TO": "Ligado a ", + "LISTENING": "A escutar...", + "SPEAKING": "A falar...", + "SERVER_NOT_FOUND": "A procurar serviço disponível", + "SERVER_NOT_CONNECTED": "Não é possível ligar ao serviço, tente mais tarde", + "SERVER_TIMEOUT": "Tempo limite de resposta", + "SERVER_ERROR": "Falha no envio, verifique a rede", + "CONNECT_TO_HOTSPOT": "Ligue o telefone ao hotspot ", + "ACCESS_VIA_BROWSER": ",aceder através do navegador ", + "WIFI_CONFIG_MODE": "Modo de configuração de rede", + "ENTERING_WIFI_CONFIG_MODE": "A entrar no modo de configuração de rede...", + "SCANNING_WIFI": "A procurar Wi-Fi...", + "NEW_VERSION": "Nova versão ", + "OTA_UPGRADE": "Atualização OTA", + "UPGRADING": "A atualizar sistema...", + "UPGRADE_FAILED": "Atualização falhada", + "ACTIVATION": "Ativação do dispositivo", + "BATTERY_LOW": "Bateria fraca", + "BATTERY_CHARGING": "A carregar", + "BATTERY_FULL": "Bateria cheia", + "BATTERY_NEED_CHARGE": "Bateria fraca, por favor carregue", + "VOLUME": "Volume ", + "MUTED": "Silenciado", + "MAX_VOLUME": "Volume máximo", + "RTC_MODE_OFF": "AEC desligado", + "RTC_MODE_ON": "AEC ligado", + "DOWNLOAD_ASSETS_FAILED": "Falha ao descarregar recursos", + "LOADING_ASSETS": "A carregar recursos...", + "PLEASE_WAIT": "Por favor aguarde...", + "FOUND_NEW_ASSETS": "Encontrados novos recursos: %s", + "HELLO_MY_FRIEND": "Olá, meu amigo!" + } +} \ No newline at end of file diff --git a/main/assets/locales/pt-PT/upgrade.ogg b/main/assets/locales/pt-PT/upgrade.ogg new file mode 100644 index 0000000..76bac60 Binary files /dev/null and b/main/assets/locales/pt-PT/upgrade.ogg differ diff --git a/main/assets/locales/pt-PT/welcome.ogg b/main/assets/locales/pt-PT/welcome.ogg new file mode 100644 index 0000000..74daf23 Binary files /dev/null and b/main/assets/locales/pt-PT/welcome.ogg differ diff --git a/main/assets/locales/pt-PT/wificonfig.ogg b/main/assets/locales/pt-PT/wificonfig.ogg new file mode 100644 index 0000000..784939f Binary files /dev/null and b/main/assets/locales/pt-PT/wificonfig.ogg differ diff --git a/main/assets/locales/ro-RO/0.ogg b/main/assets/locales/ro-RO/0.ogg new file mode 100644 index 0000000..67fd181 Binary files /dev/null and b/main/assets/locales/ro-RO/0.ogg differ diff --git a/main/assets/locales/ro-RO/1.ogg b/main/assets/locales/ro-RO/1.ogg new file mode 100644 index 0000000..291be66 Binary files /dev/null and b/main/assets/locales/ro-RO/1.ogg differ diff --git a/main/assets/locales/ro-RO/2.ogg b/main/assets/locales/ro-RO/2.ogg new file mode 100644 index 0000000..54caf95 Binary files /dev/null and b/main/assets/locales/ro-RO/2.ogg differ diff --git a/main/assets/locales/ro-RO/3.ogg b/main/assets/locales/ro-RO/3.ogg new file mode 100644 index 0000000..b93d5c1 Binary files /dev/null and b/main/assets/locales/ro-RO/3.ogg differ diff --git a/main/assets/locales/ro-RO/4.ogg b/main/assets/locales/ro-RO/4.ogg new file mode 100644 index 0000000..3feff21 Binary files /dev/null and b/main/assets/locales/ro-RO/4.ogg differ diff --git a/main/assets/locales/ro-RO/5.ogg b/main/assets/locales/ro-RO/5.ogg new file mode 100644 index 0000000..fe56930 Binary files /dev/null and b/main/assets/locales/ro-RO/5.ogg differ diff --git a/main/assets/locales/ro-RO/6.ogg b/main/assets/locales/ro-RO/6.ogg new file mode 100644 index 0000000..ed8aee9 Binary files /dev/null and b/main/assets/locales/ro-RO/6.ogg differ diff --git a/main/assets/locales/ro-RO/7.ogg b/main/assets/locales/ro-RO/7.ogg new file mode 100644 index 0000000..9ce02c0 Binary files /dev/null and b/main/assets/locales/ro-RO/7.ogg differ diff --git a/main/assets/locales/ro-RO/8.ogg b/main/assets/locales/ro-RO/8.ogg new file mode 100644 index 0000000..c5d3184 Binary files /dev/null and b/main/assets/locales/ro-RO/8.ogg differ diff --git a/main/assets/locales/ro-RO/9.ogg b/main/assets/locales/ro-RO/9.ogg new file mode 100644 index 0000000..1d156c7 Binary files /dev/null and b/main/assets/locales/ro-RO/9.ogg differ diff --git a/main/assets/locales/ro-RO/activation.ogg b/main/assets/locales/ro-RO/activation.ogg new file mode 100644 index 0000000..d2d91fb Binary files /dev/null and b/main/assets/locales/ro-RO/activation.ogg differ diff --git a/main/assets/locales/ro-RO/err_pin.ogg b/main/assets/locales/ro-RO/err_pin.ogg new file mode 100644 index 0000000..202000c Binary files /dev/null and b/main/assets/locales/ro-RO/err_pin.ogg differ diff --git a/main/assets/locales/ro-RO/err_reg.ogg b/main/assets/locales/ro-RO/err_reg.ogg new file mode 100644 index 0000000..eafcabc Binary files /dev/null and b/main/assets/locales/ro-RO/err_reg.ogg differ diff --git a/main/assets/locales/ro-RO/language.json b/main/assets/locales/ro-RO/language.json new file mode 100644 index 0000000..d8ec774 --- /dev/null +++ b/main/assets/locales/ro-RO/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "ro-RO" + }, + "strings": { + "WARNING": "Avertisment", + "INFO": "Informație", + "ERROR": "Eroare", + "VERSION": "Versiune ", + "LOADING_PROTOCOL": "Se conectează la server...", + "INITIALIZING": "Se inițializează...", + "PIN_ERROR": "Vă rugăm să introduceți cardul SIM", + "REG_ERROR": "Nu se poate accesa rețeaua, verificați starea cardului de date", + "DETECTING_MODULE": "Se detectează modulul...", + "REGISTERING_NETWORK": "Se așteaptă rețeaua...", + "CHECKING_NEW_VERSION": "Se verifică versiunea nouă...", + "CHECK_NEW_VERSION_FAILED": "Verificarea versiunii noi a eșuat, se reîncearcă în %d secunde: %s", + "SWITCH_TO_WIFI_NETWORK": "Se comută la Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Se comută la 4G...", + "STANDBY": "În așteptare", + "CONNECT_TO": "Conectare la ", + "CONNECTING": "Se conectează...", + "CONNECTED_TO": "Conectat la ", + "LISTENING": "Se ascultă...", + "SPEAKING": "Se vorbește...", + "SERVER_NOT_FOUND": "Se caută serviciul disponibil", + "SERVER_NOT_CONNECTED": "Nu se poate conecta la serviciu, încercați mai târziu", + "SERVER_TIMEOUT": "Timpul de răspuns a expirat", + "SERVER_ERROR": "Trimiterea a eșuat, verificați rețeaua", + "CONNECT_TO_HOTSPOT": "Conectați telefonul la hotspot ", + "ACCESS_VIA_BROWSER": ",accesați prin browser ", + "WIFI_CONFIG_MODE": "Modul de configurare rețea", + "ENTERING_WIFI_CONFIG_MODE": "Se intră în modul de configurare rețea...", + "SCANNING_WIFI": "Se scanează Wi-Fi...", + "NEW_VERSION": "Versiune nouă ", + "OTA_UPGRADE": "Actualizare OTA", + "UPGRADING": "Se actualizează sistemul...", + "UPGRADE_FAILED": "Actualizarea a eșuat", + "ACTIVATION": "Activarea dispozitivului", + "BATTERY_LOW": "Baterie scăzută", + "BATTERY_CHARGING": "Se încarcă", + "BATTERY_FULL": "Baterie plină", + "BATTERY_NEED_CHARGE": "Baterie scăzută, vă rugăm să încărcați", + "VOLUME": "Volum ", + "MUTED": "Silențios", + "MAX_VOLUME": "Volum maxim", + "RTC_MODE_OFF": "AEC oprit", + "RTC_MODE_ON": "AEC pornit", + "DOWNLOAD_ASSETS_FAILED": "Eșec la descărcarea resurselor", + "LOADING_ASSETS": "Se încarcă resursele...", + "PLEASE_WAIT": "Vă rugăm să așteptați...", + "FOUND_NEW_ASSETS": "S-au găsit resurse noi: %s", + "HELLO_MY_FRIEND": "Salut, prietenul meu!" + } +} \ No newline at end of file diff --git a/main/assets/locales/ro-RO/upgrade.ogg b/main/assets/locales/ro-RO/upgrade.ogg new file mode 100644 index 0000000..f4b5618 Binary files /dev/null and b/main/assets/locales/ro-RO/upgrade.ogg differ diff --git a/main/assets/locales/ro-RO/welcome.ogg b/main/assets/locales/ro-RO/welcome.ogg new file mode 100644 index 0000000..673f3d8 Binary files /dev/null and b/main/assets/locales/ro-RO/welcome.ogg differ diff --git a/main/assets/locales/ro-RO/wificonfig.ogg b/main/assets/locales/ro-RO/wificonfig.ogg new file mode 100644 index 0000000..d536cdc Binary files /dev/null and b/main/assets/locales/ro-RO/wificonfig.ogg differ diff --git a/main/assets/locales/ru-RU/0.ogg b/main/assets/locales/ru-RU/0.ogg new file mode 100644 index 0000000..4c091eb Binary files /dev/null and b/main/assets/locales/ru-RU/0.ogg differ diff --git a/main/assets/locales/ru-RU/1.ogg b/main/assets/locales/ru-RU/1.ogg new file mode 100644 index 0000000..8a6e69b Binary files /dev/null and b/main/assets/locales/ru-RU/1.ogg differ diff --git a/main/assets/locales/ru-RU/2.ogg b/main/assets/locales/ru-RU/2.ogg new file mode 100644 index 0000000..d4b29cf Binary files /dev/null and b/main/assets/locales/ru-RU/2.ogg differ diff --git a/main/assets/locales/ru-RU/3.ogg b/main/assets/locales/ru-RU/3.ogg new file mode 100644 index 0000000..6b2498b Binary files /dev/null and b/main/assets/locales/ru-RU/3.ogg differ diff --git a/main/assets/locales/ru-RU/4.ogg b/main/assets/locales/ru-RU/4.ogg new file mode 100644 index 0000000..2aa1343 Binary files /dev/null and b/main/assets/locales/ru-RU/4.ogg differ diff --git a/main/assets/locales/ru-RU/5.ogg b/main/assets/locales/ru-RU/5.ogg new file mode 100644 index 0000000..768081c Binary files /dev/null and b/main/assets/locales/ru-RU/5.ogg differ diff --git a/main/assets/locales/ru-RU/6.ogg b/main/assets/locales/ru-RU/6.ogg new file mode 100644 index 0000000..0a6e23d Binary files /dev/null and b/main/assets/locales/ru-RU/6.ogg differ diff --git a/main/assets/locales/ru-RU/7.ogg b/main/assets/locales/ru-RU/7.ogg new file mode 100644 index 0000000..060be36 Binary files /dev/null and b/main/assets/locales/ru-RU/7.ogg differ diff --git a/main/assets/locales/ru-RU/8.ogg b/main/assets/locales/ru-RU/8.ogg new file mode 100644 index 0000000..30093ae Binary files /dev/null and b/main/assets/locales/ru-RU/8.ogg differ diff --git a/main/assets/locales/ru-RU/9.ogg b/main/assets/locales/ru-RU/9.ogg new file mode 100644 index 0000000..2e07653 Binary files /dev/null and b/main/assets/locales/ru-RU/9.ogg differ diff --git a/main/assets/locales/ru-RU/activation.ogg b/main/assets/locales/ru-RU/activation.ogg new file mode 100644 index 0000000..050b12f Binary files /dev/null and b/main/assets/locales/ru-RU/activation.ogg differ diff --git a/main/assets/locales/ru-RU/err_pin.ogg b/main/assets/locales/ru-RU/err_pin.ogg new file mode 100644 index 0000000..e9f0b16 Binary files /dev/null and b/main/assets/locales/ru-RU/err_pin.ogg differ diff --git a/main/assets/locales/ru-RU/err_reg.ogg b/main/assets/locales/ru-RU/err_reg.ogg new file mode 100644 index 0000000..8be3b18 Binary files /dev/null and b/main/assets/locales/ru-RU/err_reg.ogg differ diff --git a/main/assets/locales/ru-RU/language.json b/main/assets/locales/ru-RU/language.json new file mode 100644 index 0000000..ebac606 --- /dev/null +++ b/main/assets/locales/ru-RU/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "ru-RU" + }, + "strings": { + "WARNING": "Предупреждение", + "INFO": "Информация", + "ERROR": "Ошибка", + "VERSION": "Версия ", + "LOADING_PROTOCOL": "Подключение к серверу...", + "INITIALIZING": "Инициализация...", + "PIN_ERROR": "Пожалуйста, вставьте SIM-карту", + "REG_ERROR": "Невозможно подключиться к сети, проверьте состояние карты данных", + "DETECTING_MODULE": "Обнаружение модуля...", + "REGISTERING_NETWORK": "Ожидание сети...", + "CHECKING_NEW_VERSION": "Проверка новой версии...", + "CHECK_NEW_VERSION_FAILED": "Ошибка проверки новой версии, повтор через %d секунд: %s", + "SWITCH_TO_WIFI_NETWORK": "Переключение на Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Переключение на 4G...", + "STANDBY": "Ожидание", + "CONNECT_TO": "Подключение к ", + "CONNECTING": "Подключение...", + "CONNECTED_TO": "Подключено к ", + "LISTENING": "Прослушивание...", + "SPEAKING": "Говорение...", + "SERVER_NOT_FOUND": "Поиск доступного сервиса", + "SERVER_NOT_CONNECTED": "Невозможно подключиться к сервису, попробуйте позже", + "SERVER_TIMEOUT": "Тайм-аут ответа", + "SERVER_ERROR": "Ошибка отправки, проверьте сеть", + "CONNECT_TO_HOTSPOT": "Подключите телефон к точке доступа ", + "ACCESS_VIA_BROWSER": ",доступ через браузер ", + "WIFI_CONFIG_MODE": "Режим настройки сети", + "ENTERING_WIFI_CONFIG_MODE": "Вход в режим настройки сети...", + "SCANNING_WIFI": "Сканирование Wi-Fi...", + "NEW_VERSION": "Новая версия ", + "OTA_UPGRADE": "Обновление OTA", + "UPGRADING": "Обновление системы...", + "UPGRADE_FAILED": "Обновление не удалось", + "ACTIVATION": "Активация устройства", + "BATTERY_LOW": "Низкий заряд батареи", + "BATTERY_CHARGING": "Зарядка", + "BATTERY_FULL": "Батарея полная", + "BATTERY_NEED_CHARGE": "Низкий заряд, пожалуйста, зарядите", + "VOLUME": "Громкость ", + "MUTED": "Звук отключен", + "MAX_VOLUME": "Максимальная громкость", + "RTC_MODE_OFF": "AEC выключен", + "RTC_MODE_ON": "AEC включен", + "DOWNLOAD_ASSETS_FAILED": "Не удалось загрузить ресурсы", + "LOADING_ASSETS": "Загрузка ресурсов...", + "PLEASE_WAIT": "Пожалуйста, подождите...", + "FOUND_NEW_ASSETS": "Найдены новые ресурсы: %s", + "HELLO_MY_FRIEND": "Привет, мой друг!" + } +} \ No newline at end of file diff --git a/main/assets/locales/ru-RU/upgrade.ogg b/main/assets/locales/ru-RU/upgrade.ogg new file mode 100644 index 0000000..fdb02d4 Binary files /dev/null and b/main/assets/locales/ru-RU/upgrade.ogg differ diff --git a/main/assets/locales/ru-RU/welcome.ogg b/main/assets/locales/ru-RU/welcome.ogg new file mode 100644 index 0000000..116aa37 Binary files /dev/null and b/main/assets/locales/ru-RU/welcome.ogg differ diff --git a/main/assets/locales/ru-RU/wificonfig.ogg b/main/assets/locales/ru-RU/wificonfig.ogg new file mode 100644 index 0000000..7185680 Binary files /dev/null and b/main/assets/locales/ru-RU/wificonfig.ogg differ diff --git a/main/assets/locales/sk-SK/0.ogg b/main/assets/locales/sk-SK/0.ogg new file mode 100644 index 0000000..adef2c4 Binary files /dev/null and b/main/assets/locales/sk-SK/0.ogg differ diff --git a/main/assets/locales/sk-SK/1.ogg b/main/assets/locales/sk-SK/1.ogg new file mode 100644 index 0000000..8974741 Binary files /dev/null and b/main/assets/locales/sk-SK/1.ogg differ diff --git a/main/assets/locales/sk-SK/2.ogg b/main/assets/locales/sk-SK/2.ogg new file mode 100644 index 0000000..7336f93 Binary files /dev/null and b/main/assets/locales/sk-SK/2.ogg differ diff --git a/main/assets/locales/sk-SK/3.ogg b/main/assets/locales/sk-SK/3.ogg new file mode 100644 index 0000000..ce9635e Binary files /dev/null and b/main/assets/locales/sk-SK/3.ogg differ diff --git a/main/assets/locales/sk-SK/4.ogg b/main/assets/locales/sk-SK/4.ogg new file mode 100644 index 0000000..3f8026d Binary files /dev/null and b/main/assets/locales/sk-SK/4.ogg differ diff --git a/main/assets/locales/sk-SK/5.ogg b/main/assets/locales/sk-SK/5.ogg new file mode 100644 index 0000000..dd50dd3 Binary files /dev/null and b/main/assets/locales/sk-SK/5.ogg differ diff --git a/main/assets/locales/sk-SK/6.ogg b/main/assets/locales/sk-SK/6.ogg new file mode 100644 index 0000000..8ef182a Binary files /dev/null and b/main/assets/locales/sk-SK/6.ogg differ diff --git a/main/assets/locales/sk-SK/7.ogg b/main/assets/locales/sk-SK/7.ogg new file mode 100644 index 0000000..6c7f4d5 Binary files /dev/null and b/main/assets/locales/sk-SK/7.ogg differ diff --git a/main/assets/locales/sk-SK/8.ogg b/main/assets/locales/sk-SK/8.ogg new file mode 100644 index 0000000..4533f50 Binary files /dev/null and b/main/assets/locales/sk-SK/8.ogg differ diff --git a/main/assets/locales/sk-SK/9.ogg b/main/assets/locales/sk-SK/9.ogg new file mode 100644 index 0000000..045d8f6 Binary files /dev/null and b/main/assets/locales/sk-SK/9.ogg differ diff --git a/main/assets/locales/sk-SK/activation.ogg b/main/assets/locales/sk-SK/activation.ogg new file mode 100644 index 0000000..4c780fa Binary files /dev/null and b/main/assets/locales/sk-SK/activation.ogg differ diff --git a/main/assets/locales/sk-SK/err_pin.ogg b/main/assets/locales/sk-SK/err_pin.ogg new file mode 100644 index 0000000..ee2dd69 Binary files /dev/null and b/main/assets/locales/sk-SK/err_pin.ogg differ diff --git a/main/assets/locales/sk-SK/err_reg.ogg b/main/assets/locales/sk-SK/err_reg.ogg new file mode 100644 index 0000000..0c9237f Binary files /dev/null and b/main/assets/locales/sk-SK/err_reg.ogg differ diff --git a/main/assets/locales/sk-SK/language.json b/main/assets/locales/sk-SK/language.json new file mode 100644 index 0000000..5c56f48 --- /dev/null +++ b/main/assets/locales/sk-SK/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "sk-SK" + }, + "strings": { + "WARNING": "Upozornenie", + "INFO": "Informácie", + "ERROR": "Chyba", + "VERSION": "Verzia ", + "LOADING_PROTOCOL": "Prihlasovanie...", + "INITIALIZING": "Inicializácia...", + "PIN_ERROR": "Vložte SIM kartu", + "REG_ERROR": "Nie je možné pristúpiť k sieti, skontrolujte stav SIM karty", + "DETECTING_MODULE": "Zisťovanie modulu...", + "REGISTERING_NETWORK": "Čakanie na sieť...", + "CHECKING_NEW_VERSION": "Kontrola novej verzie...", + "CHECK_NEW_VERSION_FAILED": "Kontrola novej verzie zlyhala, opakuje sa o %d sekúnd: %s", + "SWITCH_TO_WIFI_NETWORK": "Prepínanie na Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Prepínanie na 4G...", + "STANDBY": "Pohotovostný režim", + "CONNECT_TO": "Pripojenie k ", + "CONNECTING": "Pripája sa...", + "CONNECTION_SUCCESSFUL": "Pripojenie úspešné", + "CONNECTED_TO": "Pripojené k ", + "LISTENING": "Načúvanie...", + "SPEAKING": "Hovorenie...", + "SERVER_NOT_FOUND": "Hľadanie dostupnej služby", + "SERVER_NOT_CONNECTED": "Nie je možné pripojiť sa k službe, skúste to neskôr", + "SERVER_TIMEOUT": "Časový limit čakania na odpoveď vypršal", + "SERVER_ERROR": "Odosielanie zlyhalo, skontrolujte sieť", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Konfiguračná URL: ", + "WIFI_CONFIG_MODE": "Režim konfigurácie Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Vstup do režimu konfigurácie Wi-Fi...", + "SCANNING_WIFI": "Skenovanie Wi-Fi...", + "NEW_VERSION": "Nová verzia ", + "OTA_UPGRADE": "OTA aktualizácia", + "UPGRADING": "Systém sa aktualizuje...", + "UPGRADE_FAILED": "Aktualizácia zlyhala", + "ACTIVATION": "Aktivácia", + "BATTERY_LOW": "Slabá batéria", + "BATTERY_CHARGING": "Nabíjanie", + "BATTERY_FULL": "Batéria plná", + "BATTERY_NEED_CHARGE": "Slabá batéria, nabite ju", + "VOLUME": "Hlasitosť ", + "MUTED": "Stíšené", + "MAX_VOLUME": "Maximálna hlasitosť", + "RTC_MODE_OFF": "AEC vypnuté", + "RTC_MODE_ON": "AEC zapnuté", + "PLEASE_WAIT": "Počkajte prosím...", + "FOUND_NEW_ASSETS": "Nájdené nové zdroje: %s", + "DOWNLOAD_ASSETS_FAILED": "Sťahovanie zdrojov zlyhalo", + "LOADING_ASSETS": "Načítavanie zdrojov...", + "HELLO_MY_FRIEND": "Ahoj, môj priateľ!" + } +} + diff --git a/main/assets/locales/sk-SK/upgrade.ogg b/main/assets/locales/sk-SK/upgrade.ogg new file mode 100644 index 0000000..ce12dbf Binary files /dev/null and b/main/assets/locales/sk-SK/upgrade.ogg differ diff --git a/main/assets/locales/sk-SK/welcome.ogg b/main/assets/locales/sk-SK/welcome.ogg new file mode 100644 index 0000000..05b8cad Binary files /dev/null and b/main/assets/locales/sk-SK/welcome.ogg differ diff --git a/main/assets/locales/sk-SK/wificonfig.ogg b/main/assets/locales/sk-SK/wificonfig.ogg new file mode 100644 index 0000000..89906c6 Binary files /dev/null and b/main/assets/locales/sk-SK/wificonfig.ogg differ diff --git a/main/assets/locales/sl-SI/0.ogg b/main/assets/locales/sl-SI/0.ogg new file mode 100644 index 0000000..48baa9a Binary files /dev/null and b/main/assets/locales/sl-SI/0.ogg differ diff --git a/main/assets/locales/sl-SI/1.ogg b/main/assets/locales/sl-SI/1.ogg new file mode 100644 index 0000000..fcd0f70 Binary files /dev/null and b/main/assets/locales/sl-SI/1.ogg differ diff --git a/main/assets/locales/sl-SI/2.ogg b/main/assets/locales/sl-SI/2.ogg new file mode 100644 index 0000000..d5c6360 Binary files /dev/null and b/main/assets/locales/sl-SI/2.ogg differ diff --git a/main/assets/locales/sl-SI/3.ogg b/main/assets/locales/sl-SI/3.ogg new file mode 100644 index 0000000..fa0774a Binary files /dev/null and b/main/assets/locales/sl-SI/3.ogg differ diff --git a/main/assets/locales/sl-SI/4.ogg b/main/assets/locales/sl-SI/4.ogg new file mode 100644 index 0000000..95fa91f Binary files /dev/null and b/main/assets/locales/sl-SI/4.ogg differ diff --git a/main/assets/locales/sl-SI/5.ogg b/main/assets/locales/sl-SI/5.ogg new file mode 100644 index 0000000..d06e1de Binary files /dev/null and b/main/assets/locales/sl-SI/5.ogg differ diff --git a/main/assets/locales/sl-SI/6.ogg b/main/assets/locales/sl-SI/6.ogg new file mode 100644 index 0000000..d3de0e1 Binary files /dev/null and b/main/assets/locales/sl-SI/6.ogg differ diff --git a/main/assets/locales/sl-SI/7.ogg b/main/assets/locales/sl-SI/7.ogg new file mode 100644 index 0000000..36b701f Binary files /dev/null and b/main/assets/locales/sl-SI/7.ogg differ diff --git a/main/assets/locales/sl-SI/8.ogg b/main/assets/locales/sl-SI/8.ogg new file mode 100644 index 0000000..8dbdc07 Binary files /dev/null and b/main/assets/locales/sl-SI/8.ogg differ diff --git a/main/assets/locales/sl-SI/9.ogg b/main/assets/locales/sl-SI/9.ogg new file mode 100644 index 0000000..944f922 Binary files /dev/null and b/main/assets/locales/sl-SI/9.ogg differ diff --git a/main/assets/locales/sl-SI/activation.ogg b/main/assets/locales/sl-SI/activation.ogg new file mode 100644 index 0000000..73d10f3 Binary files /dev/null and b/main/assets/locales/sl-SI/activation.ogg differ diff --git a/main/assets/locales/sl-SI/err_pin.ogg b/main/assets/locales/sl-SI/err_pin.ogg new file mode 100644 index 0000000..dc692f0 Binary files /dev/null and b/main/assets/locales/sl-SI/err_pin.ogg differ diff --git a/main/assets/locales/sl-SI/err_reg.ogg b/main/assets/locales/sl-SI/err_reg.ogg new file mode 100644 index 0000000..e0ca35a Binary files /dev/null and b/main/assets/locales/sl-SI/err_reg.ogg differ diff --git a/main/assets/locales/sl-SI/language.json b/main/assets/locales/sl-SI/language.json new file mode 100644 index 0000000..0513a7d --- /dev/null +++ b/main/assets/locales/sl-SI/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "sl-SI" + }, + "strings": { + "WARNING": "Opozorilo", + "INFO": "Informacije", + "ERROR": "Napaka", + "VERSION": "Različica ", + "LOADING_PROTOCOL": "Prijava...", + "INITIALIZING": "Inicializacija...", + "PIN_ERROR": "Vstavite SIM kartico", + "REG_ERROR": "Ni mogoče dostopati do omrežja, preverite stanje SIM kartice", + "DETECTING_MODULE": "Zaznavanje modula...", + "REGISTERING_NETWORK": "Čakanje na omrežje...", + "CHECKING_NEW_VERSION": "Preverjanje nove različice...", + "CHECK_NEW_VERSION_FAILED": "Preverjanje nove različice ni uspelo, ponovni poskus čez %d sekund: %s", + "SWITCH_TO_WIFI_NETWORK": "Preklop na Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Preklop na 4G...", + "STANDBY": "Pripravljenost", + "CONNECT_TO": "Poveži se z ", + "CONNECTING": "Povezovanje...", + "CONNECTION_SUCCESSFUL": "Povezava uspešna", + "CONNECTED_TO": "Povezano z ", + "LISTENING": "Poslušanje...", + "SPEAKING": "Govorjenje...", + "SERVER_NOT_FOUND": "Iskanje razpoložljive storitve", + "SERVER_NOT_CONNECTED": "Ni se mogoče povezati s storitvijo, poskusite kasneje", + "SERVER_TIMEOUT": "Časovna omejitev čakanja na odgovor", + "SERVER_ERROR": "Pošiljanje ni uspelo, preverite omrežje", + "CONNECT_TO_HOTSPOT": "Dostopna točka: ", + "ACCESS_VIA_BROWSER": " Konfiguracijski URL: ", + "WIFI_CONFIG_MODE": "Način konfiguracije Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Vstop v način konfiguracije Wi-Fi...", + "SCANNING_WIFI": "Skeniranje Wi-Fi...", + "NEW_VERSION": "Nova različica ", + "OTA_UPGRADE": "OTA nadgradnja", + "UPGRADING": "Sistem se nadgrajuje...", + "UPGRADE_FAILED": "Nadgradnja ni uspela", + "ACTIVATION": "Aktivacija", + "BATTERY_LOW": "Nizka baterija", + "BATTERY_CHARGING": "Polnjenje", + "BATTERY_FULL": "Baterija polna", + "BATTERY_NEED_CHARGE": "Nizka baterija, napolnite", + "VOLUME": "Glasnost ", + "MUTED": "Utišano", + "MAX_VOLUME": "Največja glasnost", + "RTC_MODE_OFF": "AEC izklopljen", + "RTC_MODE_ON": "AEC vklopljen", + "PLEASE_WAIT": "Počakajte...", + "FOUND_NEW_ASSETS": "Najdeni novi viri: %s", + "DOWNLOAD_ASSETS_FAILED": "Prenos virov ni uspel", + "LOADING_ASSETS": "Nalaganje virov...", + "HELLO_MY_FRIEND": "Pozdravljeni, moj prijatelj!" + } +} + diff --git a/main/assets/locales/sl-SI/upgrade.ogg b/main/assets/locales/sl-SI/upgrade.ogg new file mode 100644 index 0000000..9c307df Binary files /dev/null and b/main/assets/locales/sl-SI/upgrade.ogg differ diff --git a/main/assets/locales/sl-SI/welcome.ogg b/main/assets/locales/sl-SI/welcome.ogg new file mode 100644 index 0000000..bab8476 Binary files /dev/null and b/main/assets/locales/sl-SI/welcome.ogg differ diff --git a/main/assets/locales/sl-SI/wificonfig.ogg b/main/assets/locales/sl-SI/wificonfig.ogg new file mode 100644 index 0000000..e29f077 Binary files /dev/null and b/main/assets/locales/sl-SI/wificonfig.ogg differ diff --git a/main/assets/locales/sr-RS/language.json b/main/assets/locales/sr-RS/language.json new file mode 100644 index 0000000..b86bf0a --- /dev/null +++ b/main/assets/locales/sr-RS/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "sr-RS" + }, + "strings": { + "WARNING": "Упозорење", + "INFO": "Информације", + "ERROR": "Грешка", + "VERSION": "Верзија ", + "LOADING_PROTOCOL": "Пријављивање...", + "INITIALIZING": "Иницијализација...", + "PIN_ERROR": "Молимо убаците SIM картицу", + "REG_ERROR": "Није могуће приступити мрежи, проверите статус SIM картице", + "DETECTING_MODULE": "Откривање модула...", + "REGISTERING_NETWORK": "Чекање мреже...", + "CHECKING_NEW_VERSION": "Провера нове верзије...", + "CHECK_NEW_VERSION_FAILED": "Провера нове верзије није успела, покушаће се поново за %d секунди: %s", + "SWITCH_TO_WIFI_NETWORK": "Пребацивање на Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Пребацивање на 4G...", + "STANDBY": "Спремност", + "CONNECT_TO": "Повежи се са ", + "CONNECTING": "Повезивање...", + "CONNECTION_SUCCESSFUL": "Успешно повезивање", + "CONNECTED_TO": "Повезано са ", + "LISTENING": "Слушање...", + "SPEAKING": "Говорење...", + "SERVER_NOT_FOUND": "Тражење доступне услуге", + "SERVER_NOT_CONNECTED": "Није могуће повезати се са услугом, покушајте касније", + "SERVER_TIMEOUT": "Истекло време чекања одговора", + "SERVER_ERROR": "Слање није успело, проверите мрежу", + "CONNECT_TO_HOTSPOT": "Приступна тачка: ", + "ACCESS_VIA_BROWSER": " URL за конфигурацију: ", + "WIFI_CONFIG_MODE": "Режим конфигурације Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Улазак у режим конфигурације Wi-Fi...", + "SCANNING_WIFI": "Скенирање Wi-Fi...", + "NEW_VERSION": "Нова верзија ", + "OTA_UPGRADE": "OTA надоградња", + "UPGRADING": "Систем се надограђује...", + "UPGRADE_FAILED": "Надоградња није успела", + "ACTIVATION": "Активација", + "BATTERY_LOW": "Слаба батерија", + "BATTERY_CHARGING": "Пуњење", + "BATTERY_FULL": "Батерија пуна", + "BATTERY_NEED_CHARGE": "Слаба батерија, молимо напуните", + "VOLUME": "Јачина звука ", + "MUTED": "Утишано", + "MAX_VOLUME": "Максимална јачина звука", + "RTC_MODE_OFF": "AEC искључен", + "RTC_MODE_ON": "AEC укључен", + "PLEASE_WAIT": "Молимо сачекајте...", + "FOUND_NEW_ASSETS": "Пронађени нови ресурси: %s", + "DOWNLOAD_ASSETS_FAILED": "Преузимање ресурса није успело", + "LOADING_ASSETS": "Учитавање ресурса...", + "HELLO_MY_FRIEND": "Здраво, пријатељу!" + } +} + diff --git a/main/assets/locales/sv-SE/0.ogg b/main/assets/locales/sv-SE/0.ogg new file mode 100644 index 0000000..af94e5b Binary files /dev/null and b/main/assets/locales/sv-SE/0.ogg differ diff --git a/main/assets/locales/sv-SE/1.ogg b/main/assets/locales/sv-SE/1.ogg new file mode 100644 index 0000000..3246d37 Binary files /dev/null and b/main/assets/locales/sv-SE/1.ogg differ diff --git a/main/assets/locales/sv-SE/2.ogg b/main/assets/locales/sv-SE/2.ogg new file mode 100644 index 0000000..db2a251 Binary files /dev/null and b/main/assets/locales/sv-SE/2.ogg differ diff --git a/main/assets/locales/sv-SE/3.ogg b/main/assets/locales/sv-SE/3.ogg new file mode 100644 index 0000000..5bfb237 Binary files /dev/null and b/main/assets/locales/sv-SE/3.ogg differ diff --git a/main/assets/locales/sv-SE/4.ogg b/main/assets/locales/sv-SE/4.ogg new file mode 100644 index 0000000..4ebccba Binary files /dev/null and b/main/assets/locales/sv-SE/4.ogg differ diff --git a/main/assets/locales/sv-SE/5.ogg b/main/assets/locales/sv-SE/5.ogg new file mode 100644 index 0000000..d45e216 Binary files /dev/null and b/main/assets/locales/sv-SE/5.ogg differ diff --git a/main/assets/locales/sv-SE/6.ogg b/main/assets/locales/sv-SE/6.ogg new file mode 100644 index 0000000..3da60f5 Binary files /dev/null and b/main/assets/locales/sv-SE/6.ogg differ diff --git a/main/assets/locales/sv-SE/7.ogg b/main/assets/locales/sv-SE/7.ogg new file mode 100644 index 0000000..85ddfab Binary files /dev/null and b/main/assets/locales/sv-SE/7.ogg differ diff --git a/main/assets/locales/sv-SE/8.ogg b/main/assets/locales/sv-SE/8.ogg new file mode 100644 index 0000000..318735f Binary files /dev/null and b/main/assets/locales/sv-SE/8.ogg differ diff --git a/main/assets/locales/sv-SE/9.ogg b/main/assets/locales/sv-SE/9.ogg new file mode 100644 index 0000000..0f60d53 Binary files /dev/null and b/main/assets/locales/sv-SE/9.ogg differ diff --git a/main/assets/locales/sv-SE/activation.ogg b/main/assets/locales/sv-SE/activation.ogg new file mode 100644 index 0000000..08a507d Binary files /dev/null and b/main/assets/locales/sv-SE/activation.ogg differ diff --git a/main/assets/locales/sv-SE/err_pin.ogg b/main/assets/locales/sv-SE/err_pin.ogg new file mode 100644 index 0000000..c3772c9 Binary files /dev/null and b/main/assets/locales/sv-SE/err_pin.ogg differ diff --git a/main/assets/locales/sv-SE/err_reg.ogg b/main/assets/locales/sv-SE/err_reg.ogg new file mode 100644 index 0000000..07fc197 Binary files /dev/null and b/main/assets/locales/sv-SE/err_reg.ogg differ diff --git a/main/assets/locales/sv-SE/language.json b/main/assets/locales/sv-SE/language.json new file mode 100644 index 0000000..444cac9 --- /dev/null +++ b/main/assets/locales/sv-SE/language.json @@ -0,0 +1,57 @@ +{ + "language": { + "type": "sv-SE" + }, + "strings": { + "WARNING": "Varning", + "INFO": "Information", + "ERROR": "Fel", + "VERSION": "Version ", + "LOADING_PROTOCOL": "Loggar in...", + "INITIALIZING": "Initierar...", + "PIN_ERROR": "Vänligen sätt in SIM-kort", + "REG_ERROR": "Kan inte komma åt nätverket, kontrollera SIM-kortets status", + "DETECTING_MODULE": "Detekterar modul...", + "REGISTERING_NETWORK": "Väntar på nätverk...", + "CHECKING_NEW_VERSION": "Kontrollerar ny version...", + "CHECK_NEW_VERSION_FAILED": "Kontroll av ny version misslyckades, försöker igen om %d sekunder: %s", + "SWITCH_TO_WIFI_NETWORK": "Byter till Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Byter till 4G...", + "STANDBY": "Standby", + "CONNECT_TO": "Anslut till ", + "CONNECTING": "Ansluter...", + "CONNECTION_SUCCESSFUL": "Anslutningen lyckades", + "CONNECTED_TO": "Ansluten till ", + "LISTENING": "Lyssnar...", + "SPEAKING": "Talar...", + "SERVER_NOT_FOUND": "Söker efter tillgänglig tjänst", + "SERVER_NOT_CONNECTED": "Kan inte ansluta till tjänsten, försök igen senare", + "SERVER_TIMEOUT": "Timeout vid väntan på svar", + "SERVER_ERROR": "Skickandet misslyckades, kontrollera nätverket", + "CONNECT_TO_HOTSPOT": "Hotspot: ", + "ACCESS_VIA_BROWSER": " Konfigurations-URL: ", + "WIFI_CONFIG_MODE": "Wi-Fi-konfigurationsläge", + "ENTERING_WIFI_CONFIG_MODE": "Går in i Wi-Fi-konfigurationsläge...", + "SCANNING_WIFI": "Skannar Wi-Fi...", + "NEW_VERSION": "Ny version ", + "OTA_UPGRADE": "OTA-uppgradering", + "UPGRADING": "Systemet uppgraderas...", + "UPGRADE_FAILED": "Uppgraderingen misslyckades", + "ACTIVATION": "Aktivering", + "BATTERY_LOW": "Lågt batteri", + "BATTERY_CHARGING": "Laddar", + "BATTERY_FULL": "Batteriet fullt", + "BATTERY_NEED_CHARGE": "Lågt batteri, vänligen ladda", + "VOLUME": "Volym ", + "MUTED": "Tystad", + "MAX_VOLUME": "Maximal volym", + "RTC_MODE_OFF": "AEC av", + "RTC_MODE_ON": "AEC på", + "PLEASE_WAIT": "Vänligen vänta...", + "FOUND_NEW_ASSETS": "Hittade nya resurser: %s", + "DOWNLOAD_ASSETS_FAILED": "Nedladdning av resurser misslyckades", + "LOADING_ASSETS": "Laddar resurser...", + "HELLO_MY_FRIEND": "Hej, min vän!" + } +} + diff --git a/main/assets/locales/sv-SE/upgrade.ogg b/main/assets/locales/sv-SE/upgrade.ogg new file mode 100644 index 0000000..db4d02d Binary files /dev/null and b/main/assets/locales/sv-SE/upgrade.ogg differ diff --git a/main/assets/locales/sv-SE/welcome.ogg b/main/assets/locales/sv-SE/welcome.ogg new file mode 100644 index 0000000..9407896 Binary files /dev/null and b/main/assets/locales/sv-SE/welcome.ogg differ diff --git a/main/assets/locales/sv-SE/wificonfig.ogg b/main/assets/locales/sv-SE/wificonfig.ogg new file mode 100644 index 0000000..f232108 Binary files /dev/null and b/main/assets/locales/sv-SE/wificonfig.ogg differ diff --git a/main/assets/locales/th-TH/0.ogg b/main/assets/locales/th-TH/0.ogg new file mode 100644 index 0000000..15e2544 Binary files /dev/null and b/main/assets/locales/th-TH/0.ogg differ diff --git a/main/assets/locales/th-TH/1.ogg b/main/assets/locales/th-TH/1.ogg new file mode 100644 index 0000000..87753b3 Binary files /dev/null and b/main/assets/locales/th-TH/1.ogg differ diff --git a/main/assets/locales/th-TH/2.ogg b/main/assets/locales/th-TH/2.ogg new file mode 100644 index 0000000..057a6f3 Binary files /dev/null and b/main/assets/locales/th-TH/2.ogg differ diff --git a/main/assets/locales/th-TH/3.ogg b/main/assets/locales/th-TH/3.ogg new file mode 100644 index 0000000..104d51b Binary files /dev/null and b/main/assets/locales/th-TH/3.ogg differ diff --git a/main/assets/locales/th-TH/4.ogg b/main/assets/locales/th-TH/4.ogg new file mode 100644 index 0000000..a35befc Binary files /dev/null and b/main/assets/locales/th-TH/4.ogg differ diff --git a/main/assets/locales/th-TH/5.ogg b/main/assets/locales/th-TH/5.ogg new file mode 100644 index 0000000..8eb3b5b Binary files /dev/null and b/main/assets/locales/th-TH/5.ogg differ diff --git a/main/assets/locales/th-TH/6.ogg b/main/assets/locales/th-TH/6.ogg new file mode 100644 index 0000000..b8cbbe0 Binary files /dev/null and b/main/assets/locales/th-TH/6.ogg differ diff --git a/main/assets/locales/th-TH/7.ogg b/main/assets/locales/th-TH/7.ogg new file mode 100644 index 0000000..e93c9a4 Binary files /dev/null and b/main/assets/locales/th-TH/7.ogg differ diff --git a/main/assets/locales/th-TH/8.ogg b/main/assets/locales/th-TH/8.ogg new file mode 100644 index 0000000..becde0e Binary files /dev/null and b/main/assets/locales/th-TH/8.ogg differ diff --git a/main/assets/locales/th-TH/9.ogg b/main/assets/locales/th-TH/9.ogg new file mode 100644 index 0000000..319ef67 Binary files /dev/null and b/main/assets/locales/th-TH/9.ogg differ diff --git a/main/assets/locales/th-TH/activation.ogg b/main/assets/locales/th-TH/activation.ogg new file mode 100644 index 0000000..983e4d8 Binary files /dev/null and b/main/assets/locales/th-TH/activation.ogg differ diff --git a/main/assets/locales/th-TH/err_pin.ogg b/main/assets/locales/th-TH/err_pin.ogg new file mode 100644 index 0000000..059cc8f Binary files /dev/null and b/main/assets/locales/th-TH/err_pin.ogg differ diff --git a/main/assets/locales/th-TH/err_reg.ogg b/main/assets/locales/th-TH/err_reg.ogg new file mode 100644 index 0000000..042c47f Binary files /dev/null and b/main/assets/locales/th-TH/err_reg.ogg differ diff --git a/main/assets/locales/th-TH/language.json b/main/assets/locales/th-TH/language.json new file mode 100644 index 0000000..e97fed1 --- /dev/null +++ b/main/assets/locales/th-TH/language.json @@ -0,0 +1,56 @@ +{ + "language": { + "type": "th-TH" + }, + "strings": { + "WARNING": "คำเตือน", + "INFO": "ข้อมูล", + "ERROR": "ข้อผิดพลาด", + "VERSION": "เวอร์ชัน ", + "LOADING_PROTOCOL": "กำลังเข้าสู่ระบบ...", + "INITIALIZING": "กำลังเริ่มต้นระบบ...", + "PIN_ERROR": "กรุณาใส่ซิมการ์ด", + "REG_ERROR": "ไม่สามารถเข้าถึงเครือข่ายได้ กรุณาตรวจสอบสถานะซิมการ์ด", + "DETECTING_MODULE": "กำลังตรวจจับโมดูล...", + "REGISTERING_NETWORK": "กำลังรอเครือข่าย...", + "CHECKING_NEW_VERSION": "กำลังตรวจสอบเวอร์ชันใหม่...", + "CHECK_NEW_VERSION_FAILED": "การตรวจสอบเวอร์ชันใหม่ล้มเหลว จะลองใหม่ใน %d วินาที: %s", + "SWITCH_TO_WIFI_NETWORK": "กำลังเปลี่ยนเป็น Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "กำลังเปลี่ยนเป็น 4G...", + "STANDBY": "พร้อม", + "CONNECT_TO": "เชื่อมต่อกับ ", + "CONNECTING": "กำลังเชื่อมต่อ...", + "CONNECTION_SUCCESSFUL": "เชื่อมต่อสำเร็จ", + "CONNECTED_TO": "เชื่อมต่อกับ ", + "LISTENING": "กำลังฟัง...", + "SPEAKING": "กำลังพูด...", + "SERVER_NOT_FOUND": "กำลังค้นหาบริการที่ใช้งานได้", + "SERVER_NOT_CONNECTED": "ไม่สามารถเชื่อมต่อกับบริการได้ กรุณาลองใหม่ในภายหลัง", + "SERVER_TIMEOUT": "หมดเวลารอการตอบกลับ", + "SERVER_ERROR": "การส่งข้อมูลล้มเหลว กรุณาตรวจสอบเครือข่าย", + "CONNECT_TO_HOTSPOT": "ฮอตสปอต: ", + "ACCESS_VIA_BROWSER": " URL การตั้งค่า: ", + "WIFI_CONFIG_MODE": "โหมดการตั้งค่า Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "กำลังเข้าสู่โหมดการตั้งค่า Wi-Fi...", + "SCANNING_WIFI": "กำลังสแกน Wi-Fi...", + "NEW_VERSION": "เวอร์ชันใหม่ ", + "OTA_UPGRADE": "การอัปเกรด OTA", + "UPGRADING": "ระบบกำลังอัปเกรด...", + "UPGRADE_FAILED": "การอัปเกรดล้มเหลว", + "ACTIVATION": "การเปิดใช้งาน", + "BATTERY_LOW": "แบตเตอรี่ต่ำ", + "BATTERY_CHARGING": "กำลังชาร์จ", + "BATTERY_FULL": "แบตเตอรี่เต็ม", + "BATTERY_NEED_CHARGE": "แบตเตอรี่ต่ำ กรุณาชาร์จ", + "VOLUME": "เสียง ", + "MUTED": "ปิดเสียง", + "MAX_VOLUME": "เสียงสูงสุด", + "RTC_MODE_OFF": "ปิด AEC", + "RTC_MODE_ON": "เปิด AEC", + "DOWNLOAD_ASSETS_FAILED": "ดาวน์โหลดทรัพยากรล้มเหลว", + "LOADING_ASSETS": "กำลังโหลดทรัพยากร...", + "PLEASE_WAIT": "กรุณารอสักครู่...", + "FOUND_NEW_ASSETS": "พบทรัพยากรใหม่: %s", + "HELLO_MY_FRIEND": "สวัสดี เพื่อนของฉัน!" + } +} \ No newline at end of file diff --git a/main/assets/locales/th-TH/upgrade.ogg b/main/assets/locales/th-TH/upgrade.ogg new file mode 100644 index 0000000..e024638 Binary files /dev/null and b/main/assets/locales/th-TH/upgrade.ogg differ diff --git a/main/assets/locales/th-TH/welcome.ogg b/main/assets/locales/th-TH/welcome.ogg new file mode 100644 index 0000000..0b32b80 Binary files /dev/null and b/main/assets/locales/th-TH/welcome.ogg differ diff --git a/main/assets/locales/th-TH/wificonfig.ogg b/main/assets/locales/th-TH/wificonfig.ogg new file mode 100644 index 0000000..984d217 Binary files /dev/null and b/main/assets/locales/th-TH/wificonfig.ogg differ diff --git a/main/assets/locales/tr-TR/0.ogg b/main/assets/locales/tr-TR/0.ogg new file mode 100644 index 0000000..9ab9285 Binary files /dev/null and b/main/assets/locales/tr-TR/0.ogg differ diff --git a/main/assets/locales/tr-TR/1.ogg b/main/assets/locales/tr-TR/1.ogg new file mode 100644 index 0000000..131d774 Binary files /dev/null and b/main/assets/locales/tr-TR/1.ogg differ diff --git a/main/assets/locales/tr-TR/2.ogg b/main/assets/locales/tr-TR/2.ogg new file mode 100644 index 0000000..5e80f6e Binary files /dev/null and b/main/assets/locales/tr-TR/2.ogg differ diff --git a/main/assets/locales/tr-TR/3.ogg b/main/assets/locales/tr-TR/3.ogg new file mode 100644 index 0000000..bdc0550 Binary files /dev/null and b/main/assets/locales/tr-TR/3.ogg differ diff --git a/main/assets/locales/tr-TR/4.ogg b/main/assets/locales/tr-TR/4.ogg new file mode 100644 index 0000000..fd39d2d Binary files /dev/null and b/main/assets/locales/tr-TR/4.ogg differ diff --git a/main/assets/locales/tr-TR/5.ogg b/main/assets/locales/tr-TR/5.ogg new file mode 100644 index 0000000..30d093e Binary files /dev/null and b/main/assets/locales/tr-TR/5.ogg differ diff --git a/main/assets/locales/tr-TR/6.ogg b/main/assets/locales/tr-TR/6.ogg new file mode 100644 index 0000000..95a6f6d Binary files /dev/null and b/main/assets/locales/tr-TR/6.ogg differ diff --git a/main/assets/locales/tr-TR/7.ogg b/main/assets/locales/tr-TR/7.ogg new file mode 100644 index 0000000..9ba5ebc Binary files /dev/null and b/main/assets/locales/tr-TR/7.ogg differ diff --git a/main/assets/locales/tr-TR/8.ogg b/main/assets/locales/tr-TR/8.ogg new file mode 100644 index 0000000..9a4d8c8 Binary files /dev/null and b/main/assets/locales/tr-TR/8.ogg differ diff --git a/main/assets/locales/tr-TR/9.ogg b/main/assets/locales/tr-TR/9.ogg new file mode 100644 index 0000000..af30078 Binary files /dev/null and b/main/assets/locales/tr-TR/9.ogg differ diff --git a/main/assets/locales/tr-TR/activation.ogg b/main/assets/locales/tr-TR/activation.ogg new file mode 100644 index 0000000..f8bf34e Binary files /dev/null and b/main/assets/locales/tr-TR/activation.ogg differ diff --git a/main/assets/locales/tr-TR/err_pin.ogg b/main/assets/locales/tr-TR/err_pin.ogg new file mode 100644 index 0000000..6e5831e Binary files /dev/null and b/main/assets/locales/tr-TR/err_pin.ogg differ diff --git a/main/assets/locales/tr-TR/err_reg.ogg b/main/assets/locales/tr-TR/err_reg.ogg new file mode 100644 index 0000000..91fc7ff Binary files /dev/null and b/main/assets/locales/tr-TR/err_reg.ogg differ diff --git a/main/assets/locales/tr-TR/language.json b/main/assets/locales/tr-TR/language.json new file mode 100644 index 0000000..4d0f70f --- /dev/null +++ b/main/assets/locales/tr-TR/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "tr-TR" + }, + "strings": { + "WARNING": "Uyarı", + "INFO": "Bilgi", + "ERROR": "Hata", + "VERSION": "Sürüm ", + "LOADING_PROTOCOL": "Sunucuya bağlanıyor...", + "INITIALIZING": "Başlatılıyor...", + "PIN_ERROR": "Lütfen SIM kartı takın", + "REG_ERROR": "Ağa erişilemiyor, veri kartı durumunu kontrol edin", + "DETECTING_MODULE": "Modül algılanıyor...", + "REGISTERING_NETWORK": "Ağ bekleniyor...", + "CHECKING_NEW_VERSION": "Yeni sürüm kontrol ediliyor...", + "CHECK_NEW_VERSION_FAILED": "Yeni sürüm kontrolü başarısız, %d saniye sonra tekrar denenecek: %s", + "SWITCH_TO_WIFI_NETWORK": "Wi-Fi'ye geçiliyor...", + "SWITCH_TO_4G_NETWORK": "4G'ye geçiliyor...", + "STANDBY": "Bekleme", + "CONNECT_TO": "Bağlan ", + "CONNECTING": "Bağlanıyor...", + "CONNECTED_TO": "Bağlandı ", + "LISTENING": "Dinleniyor...", + "SPEAKING": "Konuşuluyor...", + "SERVER_NOT_FOUND": "Mevcut hizmet aranıyor", + "SERVER_NOT_CONNECTED": "Hizmete bağlanılamıyor, lütfen daha sonra deneyin", + "SERVER_TIMEOUT": "Yanıt zaman aşımı", + "SERVER_ERROR": "Gönderme başarısız, ağı kontrol edin", + "CONNECT_TO_HOTSPOT": "Telefonu hotspot'a bağlayın ", + "ACCESS_VIA_BROWSER": ",tarayıcı üzerinden erişin ", + "WIFI_CONFIG_MODE": "Ağ yapılandırma modu", + "ENTERING_WIFI_CONFIG_MODE": "Ağ yapılandırma moduna giriliyor...", + "SCANNING_WIFI": "Wi-Fi taranıyor...", + "NEW_VERSION": "Yeni sürüm ", + "OTA_UPGRADE": "OTA güncelleme", + "UPGRADING": "Sistem güncelleniyor...", + "UPGRADE_FAILED": "Güncelleme başarısız", + "ACTIVATION": "Cihaz aktivasyonu", + "BATTERY_LOW": "Pil düşük", + "BATTERY_CHARGING": "Şarj oluyor", + "BATTERY_FULL": "Pil dolu", + "BATTERY_NEED_CHARGE": "Pil düşük, lütfen şarj edin", + "VOLUME": "Ses ", + "MUTED": "Sessiz", + "MAX_VOLUME": "Maksimum ses", + "RTC_MODE_OFF": "AEC kapalı", + "RTC_MODE_ON": "AEC açık", + "DOWNLOAD_ASSETS_FAILED": "Varlıklar indirilemedi", + "LOADING_ASSETS": "Varlıklar yükleniyor...", + "PLEASE_WAIT": "Lütfen bekleyin...", + "FOUND_NEW_ASSETS": "Yeni varlıklar bulundu: %s", + "HELLO_MY_FRIEND": "Merhaba, arkadaşım!" + } +} \ No newline at end of file diff --git a/main/assets/locales/tr-TR/upgrade.ogg b/main/assets/locales/tr-TR/upgrade.ogg new file mode 100644 index 0000000..57215bd Binary files /dev/null and b/main/assets/locales/tr-TR/upgrade.ogg differ diff --git a/main/assets/locales/tr-TR/welcome.ogg b/main/assets/locales/tr-TR/welcome.ogg new file mode 100644 index 0000000..fedd21c Binary files /dev/null and b/main/assets/locales/tr-TR/welcome.ogg differ diff --git a/main/assets/locales/tr-TR/wificonfig.ogg b/main/assets/locales/tr-TR/wificonfig.ogg new file mode 100644 index 0000000..c898adc Binary files /dev/null and b/main/assets/locales/tr-TR/wificonfig.ogg differ diff --git a/main/assets/locales/uk-UA/0.ogg b/main/assets/locales/uk-UA/0.ogg new file mode 100644 index 0000000..f4ea62c Binary files /dev/null and b/main/assets/locales/uk-UA/0.ogg differ diff --git a/main/assets/locales/uk-UA/1.ogg b/main/assets/locales/uk-UA/1.ogg new file mode 100644 index 0000000..94bfed5 Binary files /dev/null and b/main/assets/locales/uk-UA/1.ogg differ diff --git a/main/assets/locales/uk-UA/2.ogg b/main/assets/locales/uk-UA/2.ogg new file mode 100644 index 0000000..e6226d5 Binary files /dev/null and b/main/assets/locales/uk-UA/2.ogg differ diff --git a/main/assets/locales/uk-UA/3.ogg b/main/assets/locales/uk-UA/3.ogg new file mode 100644 index 0000000..50f7faa Binary files /dev/null and b/main/assets/locales/uk-UA/3.ogg differ diff --git a/main/assets/locales/uk-UA/4.ogg b/main/assets/locales/uk-UA/4.ogg new file mode 100644 index 0000000..d3f9d7f Binary files /dev/null and b/main/assets/locales/uk-UA/4.ogg differ diff --git a/main/assets/locales/uk-UA/5.ogg b/main/assets/locales/uk-UA/5.ogg new file mode 100644 index 0000000..712b0a0 Binary files /dev/null and b/main/assets/locales/uk-UA/5.ogg differ diff --git a/main/assets/locales/uk-UA/6.ogg b/main/assets/locales/uk-UA/6.ogg new file mode 100644 index 0000000..7a01d5f Binary files /dev/null and b/main/assets/locales/uk-UA/6.ogg differ diff --git a/main/assets/locales/uk-UA/7.ogg b/main/assets/locales/uk-UA/7.ogg new file mode 100644 index 0000000..4f3d5b2 Binary files /dev/null and b/main/assets/locales/uk-UA/7.ogg differ diff --git a/main/assets/locales/uk-UA/8.ogg b/main/assets/locales/uk-UA/8.ogg new file mode 100644 index 0000000..9577bc7 Binary files /dev/null and b/main/assets/locales/uk-UA/8.ogg differ diff --git a/main/assets/locales/uk-UA/9.ogg b/main/assets/locales/uk-UA/9.ogg new file mode 100644 index 0000000..dbaf9d6 Binary files /dev/null and b/main/assets/locales/uk-UA/9.ogg differ diff --git a/main/assets/locales/uk-UA/activation.ogg b/main/assets/locales/uk-UA/activation.ogg new file mode 100644 index 0000000..446e020 Binary files /dev/null and b/main/assets/locales/uk-UA/activation.ogg differ diff --git a/main/assets/locales/uk-UA/err_pin.ogg b/main/assets/locales/uk-UA/err_pin.ogg new file mode 100644 index 0000000..dd7d402 Binary files /dev/null and b/main/assets/locales/uk-UA/err_pin.ogg differ diff --git a/main/assets/locales/uk-UA/err_reg.ogg b/main/assets/locales/uk-UA/err_reg.ogg new file mode 100644 index 0000000..ffe1a4c Binary files /dev/null and b/main/assets/locales/uk-UA/err_reg.ogg differ diff --git a/main/assets/locales/uk-UA/language.json b/main/assets/locales/uk-UA/language.json new file mode 100644 index 0000000..d844a38 --- /dev/null +++ b/main/assets/locales/uk-UA/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "uk-UA" + }, + "strings": { + "WARNING": "Попередження", + "INFO": "Інформація", + "ERROR": "Помилка", + "VERSION": "Версія ", + "LOADING_PROTOCOL": "Підключення до сервера...", + "INITIALIZING": "Ініціалізація...", + "PIN_ERROR": "Будь ласка, вставте SIM-карту", + "REG_ERROR": "Неможливо отримати доступ до мережі, перевірте стан карти даних", + "DETECTING_MODULE": "Виявлення модуля...", + "REGISTERING_NETWORK": "Очікування мережі...", + "CHECKING_NEW_VERSION": "Перевірка нової версії...", + "CHECK_NEW_VERSION_FAILED": "Перевірка нової версії не вдалася, повтор через %d секунд: %s", + "SWITCH_TO_WIFI_NETWORK": "Перемикання на Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Перемикання на 4G...", + "STANDBY": "Очікування", + "CONNECT_TO": "Підключитися до ", + "CONNECTING": "Підключення...", + "CONNECTED_TO": "Підключено до ", + "LISTENING": "Прослуховування...", + "SPEAKING": "Говоріння...", + "SERVER_NOT_FOUND": "Пошук доступного сервісу", + "SERVER_NOT_CONNECTED": "Неможливо підключитися до сервісу, спробуйте пізніше", + "SERVER_TIMEOUT": "Час очікування відповіді", + "SERVER_ERROR": "Помилка відправки, перевірте мережу", + "CONNECT_TO_HOTSPOT": "Підключіть телефон до точки доступу ", + "ACCESS_VIA_BROWSER": ",доступ через браузер ", + "WIFI_CONFIG_MODE": "Режим налаштування мережі", + "ENTERING_WIFI_CONFIG_MODE": "Вхід у режим налаштування мережі...", + "SCANNING_WIFI": "Сканування Wi-Fi...", + "NEW_VERSION": "Нова версія ", + "OTA_UPGRADE": "Оновлення OTA", + "UPGRADING": "Оновлення системи...", + "UPGRADE_FAILED": "Оновлення не вдалося", + "ACTIVATION": "Активація пристрою", + "BATTERY_LOW": "Низький заряд батареї", + "BATTERY_CHARGING": "Зарядка", + "BATTERY_FULL": "Батарея повна", + "BATTERY_NEED_CHARGE": "Низький заряд, будь ласка, зарядіть", + "VOLUME": "Гучність ", + "MUTED": "Звук вимкнено", + "MAX_VOLUME": "Максимальна гучність", + "RTC_MODE_OFF": "AEC вимкнено", + "RTC_MODE_ON": "AEC увімкнено", + "DOWNLOAD_ASSETS_FAILED": "Не вдалося завантажити ресурси", + "LOADING_ASSETS": "Завантаження ресурсів...", + "PLEASE_WAIT": "Будь ласка, зачекайте...", + "FOUND_NEW_ASSETS": "Знайдено нові ресурси: %s", + "HELLO_MY_FRIEND": "Привіт, мій друже!" + } +} \ No newline at end of file diff --git a/main/assets/locales/uk-UA/upgrade.ogg b/main/assets/locales/uk-UA/upgrade.ogg new file mode 100644 index 0000000..5a41be8 Binary files /dev/null and b/main/assets/locales/uk-UA/upgrade.ogg differ diff --git a/main/assets/locales/uk-UA/welcome.ogg b/main/assets/locales/uk-UA/welcome.ogg new file mode 100644 index 0000000..e04ca00 Binary files /dev/null and b/main/assets/locales/uk-UA/welcome.ogg differ diff --git a/main/assets/locales/uk-UA/wificonfig.ogg b/main/assets/locales/uk-UA/wificonfig.ogg new file mode 100644 index 0000000..c1d5d90 Binary files /dev/null and b/main/assets/locales/uk-UA/wificonfig.ogg differ diff --git a/main/assets/locales/vi-VN/0.ogg b/main/assets/locales/vi-VN/0.ogg new file mode 100644 index 0000000..c6c0418 Binary files /dev/null and b/main/assets/locales/vi-VN/0.ogg differ diff --git a/main/assets/locales/vi-VN/1.ogg b/main/assets/locales/vi-VN/1.ogg new file mode 100644 index 0000000..4774b06 Binary files /dev/null and b/main/assets/locales/vi-VN/1.ogg differ diff --git a/main/assets/locales/vi-VN/2.ogg b/main/assets/locales/vi-VN/2.ogg new file mode 100644 index 0000000..592e9a4 Binary files /dev/null and b/main/assets/locales/vi-VN/2.ogg differ diff --git a/main/assets/locales/vi-VN/3.ogg b/main/assets/locales/vi-VN/3.ogg new file mode 100644 index 0000000..6825973 Binary files /dev/null and b/main/assets/locales/vi-VN/3.ogg differ diff --git a/main/assets/locales/vi-VN/4.ogg b/main/assets/locales/vi-VN/4.ogg new file mode 100644 index 0000000..983e48a Binary files /dev/null and b/main/assets/locales/vi-VN/4.ogg differ diff --git a/main/assets/locales/vi-VN/5.ogg b/main/assets/locales/vi-VN/5.ogg new file mode 100644 index 0000000..fd950a0 Binary files /dev/null and b/main/assets/locales/vi-VN/5.ogg differ diff --git a/main/assets/locales/vi-VN/6.ogg b/main/assets/locales/vi-VN/6.ogg new file mode 100644 index 0000000..8158cfc Binary files /dev/null and b/main/assets/locales/vi-VN/6.ogg differ diff --git a/main/assets/locales/vi-VN/7.ogg b/main/assets/locales/vi-VN/7.ogg new file mode 100644 index 0000000..ca03b3e Binary files /dev/null and b/main/assets/locales/vi-VN/7.ogg differ diff --git a/main/assets/locales/vi-VN/8.ogg b/main/assets/locales/vi-VN/8.ogg new file mode 100644 index 0000000..d359674 Binary files /dev/null and b/main/assets/locales/vi-VN/8.ogg differ diff --git a/main/assets/locales/vi-VN/9.ogg b/main/assets/locales/vi-VN/9.ogg new file mode 100644 index 0000000..6c6dd0b Binary files /dev/null and b/main/assets/locales/vi-VN/9.ogg differ diff --git a/main/assets/locales/vi-VN/activation.ogg b/main/assets/locales/vi-VN/activation.ogg new file mode 100644 index 0000000..a3871b8 Binary files /dev/null and b/main/assets/locales/vi-VN/activation.ogg differ diff --git a/main/assets/locales/vi-VN/err_pin.ogg b/main/assets/locales/vi-VN/err_pin.ogg new file mode 100644 index 0000000..16e42a0 Binary files /dev/null and b/main/assets/locales/vi-VN/err_pin.ogg differ diff --git a/main/assets/locales/vi-VN/err_reg.ogg b/main/assets/locales/vi-VN/err_reg.ogg new file mode 100644 index 0000000..00b6bab Binary files /dev/null and b/main/assets/locales/vi-VN/err_reg.ogg differ diff --git a/main/assets/locales/vi-VN/language.json b/main/assets/locales/vi-VN/language.json new file mode 100644 index 0000000..e010b7b --- /dev/null +++ b/main/assets/locales/vi-VN/language.json @@ -0,0 +1,56 @@ +{ + "language": { + "type": "vi-VN" + }, + "strings": { + "WARNING": "Cảnh báo", + "INFO": "Thông tin", + "ERROR": "Lỗi", + "VERSION": "Phiên bản ", + "LOADING_PROTOCOL": "Đang đăng nhập...", + "INITIALIZING": "Đang khởi tạo...", + "PIN_ERROR": "Vui lòng cắm thẻ SIM", + "REG_ERROR": "Không thể truy cập mạng, vui lòng kiểm tra trạng thái thẻ SIM", + "DETECTING_MODULE": "Đang phát hiện module...", + "REGISTERING_NETWORK": "Đang chờ mạng...", + "CHECKING_NEW_VERSION": "Đang kiểm tra phiên bản mới...", + "CHECK_NEW_VERSION_FAILED": "Kiểm tra phiên bản mới thất bại, sẽ thử lại sau %d giây: %s", + "SWITCH_TO_WIFI_NETWORK": "Đang chuyển sang Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "Đang chuyển sang 4G...", + "STANDBY": "Chờ", + "CONNECT_TO": "Kết nối đến ", + "CONNECTING": "Đang kết nối...", + "CONNECTION_SUCCESSFUL": "Kết nối thành công", + "CONNECTED_TO": "Đã kết nối đến ", + "LISTENING": "Đang lắng nghe...", + "SPEAKING": "Đang nói...", + "SERVER_NOT_FOUND": "Đang tìm dịch vụ khả dụng", + "SERVER_NOT_CONNECTED": "Không thể kết nối đến dịch vụ, vui lòng thử lại sau", + "SERVER_TIMEOUT": "Hết thời gian chờ phản hồi", + "SERVER_ERROR": "Gửi thất bại, vui lòng kiểm tra mạng", + "CONNECT_TO_HOTSPOT": "Điểm phát sóng: ", + "ACCESS_VIA_BROWSER": " URL cấu hình: ", + "WIFI_CONFIG_MODE": "Chế độ cấu hình Wi-Fi", + "ENTERING_WIFI_CONFIG_MODE": "Đang vào chế độ cấu hình Wi-Fi...", + "SCANNING_WIFI": "Đang quét Wi-Fi...", + "NEW_VERSION": "Phiên bản mới ", + "OTA_UPGRADE": "Nâng cấp OTA", + "UPGRADING": "Hệ thống đang nâng cấp...", + "UPGRADE_FAILED": "Nâng cấp thất bại", + "ACTIVATION": "Kích hoạt", + "BATTERY_LOW": "Pin yếu", + "BATTERY_CHARGING": "Đang sạc", + "BATTERY_FULL": "Pin đầy", + "BATTERY_NEED_CHARGE": "Pin yếu, vui lòng sạc", + "VOLUME": "Âm lượng ", + "MUTED": "Tắt tiếng", + "MAX_VOLUME": "Âm lượng tối đa", + "RTC_MODE_OFF": "Tắt AEC", + "RTC_MODE_ON": "Bật AEC", + "DOWNLOAD_ASSETS_FAILED": "Tải xuống tài nguyên thất bại", + "LOADING_ASSETS": "Đang tải tài nguyên...", + "PLEASE_WAIT": "Vui lòng đợi...", + "FOUND_NEW_ASSETS": "Tìm thấy tài nguyên mới: %s", + "HELLO_MY_FRIEND": "Xin chào, bạn của tôi!" + } +} \ No newline at end of file diff --git a/main/assets/locales/vi-VN/upgrade.ogg b/main/assets/locales/vi-VN/upgrade.ogg new file mode 100644 index 0000000..1d41e98 Binary files /dev/null and b/main/assets/locales/vi-VN/upgrade.ogg differ diff --git a/main/assets/locales/vi-VN/welcome.ogg b/main/assets/locales/vi-VN/welcome.ogg new file mode 100644 index 0000000..ae12cc3 Binary files /dev/null and b/main/assets/locales/vi-VN/welcome.ogg differ diff --git a/main/assets/locales/vi-VN/wificonfig.ogg b/main/assets/locales/vi-VN/wificonfig.ogg new file mode 100644 index 0000000..08c3cb5 Binary files /dev/null and b/main/assets/locales/vi-VN/wificonfig.ogg differ diff --git a/main/assets/locales/zh-CN/0.ogg b/main/assets/locales/zh-CN/0.ogg new file mode 100644 index 0000000..0cb1247 Binary files /dev/null and b/main/assets/locales/zh-CN/0.ogg differ diff --git a/main/assets/locales/zh-CN/1.ogg b/main/assets/locales/zh-CN/1.ogg new file mode 100644 index 0000000..858af34 Binary files /dev/null and b/main/assets/locales/zh-CN/1.ogg differ diff --git a/main/assets/locales/zh-CN/2.ogg b/main/assets/locales/zh-CN/2.ogg new file mode 100644 index 0000000..72f53aa Binary files /dev/null and b/main/assets/locales/zh-CN/2.ogg differ diff --git a/main/assets/locales/zh-CN/3.ogg b/main/assets/locales/zh-CN/3.ogg new file mode 100644 index 0000000..848af11 Binary files /dev/null and b/main/assets/locales/zh-CN/3.ogg differ diff --git a/main/assets/locales/zh-CN/4.ogg b/main/assets/locales/zh-CN/4.ogg new file mode 100644 index 0000000..39b3eee Binary files /dev/null and b/main/assets/locales/zh-CN/4.ogg differ diff --git a/main/assets/locales/zh-CN/5.ogg b/main/assets/locales/zh-CN/5.ogg new file mode 100644 index 0000000..9230358 Binary files /dev/null and b/main/assets/locales/zh-CN/5.ogg differ diff --git a/main/assets/locales/zh-CN/6.ogg b/main/assets/locales/zh-CN/6.ogg new file mode 100644 index 0000000..9ecb574 Binary files /dev/null and b/main/assets/locales/zh-CN/6.ogg differ diff --git a/main/assets/locales/zh-CN/7.ogg b/main/assets/locales/zh-CN/7.ogg new file mode 100644 index 0000000..6348799 Binary files /dev/null and b/main/assets/locales/zh-CN/7.ogg differ diff --git a/main/assets/locales/zh-CN/8.ogg b/main/assets/locales/zh-CN/8.ogg new file mode 100644 index 0000000..67fc7a9 Binary files /dev/null and b/main/assets/locales/zh-CN/8.ogg differ diff --git a/main/assets/locales/zh-CN/9.ogg b/main/assets/locales/zh-CN/9.ogg new file mode 100644 index 0000000..a7769d9 Binary files /dev/null and b/main/assets/locales/zh-CN/9.ogg differ diff --git a/main/assets/locales/zh-CN/activation.ogg b/main/assets/locales/zh-CN/activation.ogg new file mode 100644 index 0000000..33291af Binary files /dev/null and b/main/assets/locales/zh-CN/activation.ogg differ diff --git a/main/assets/locales/zh-CN/err_pin.ogg b/main/assets/locales/zh-CN/err_pin.ogg new file mode 100644 index 0000000..e455244 Binary files /dev/null and b/main/assets/locales/zh-CN/err_pin.ogg differ diff --git a/main/assets/locales/zh-CN/err_reg.ogg b/main/assets/locales/zh-CN/err_reg.ogg new file mode 100644 index 0000000..a3456f1 Binary files /dev/null and b/main/assets/locales/zh-CN/err_reg.ogg differ diff --git a/main/assets/locales/zh-CN/language.json b/main/assets/locales/zh-CN/language.json new file mode 100644 index 0000000..9eb619d --- /dev/null +++ b/main/assets/locales/zh-CN/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "zh-CN" + }, + "strings": { + "WARNING": "警告", + "INFO": "信息", + "ERROR": "错误", + "VERSION": "版本 ", + "LOADING_PROTOCOL": "登录服务器...", + "INITIALIZING": "正在初始化...", + "PIN_ERROR": "请插入 SIM 卡", + "REG_ERROR": "无法接入网络,请检查流量卡状态", + "DETECTING_MODULE": "检测模组...", + "REGISTERING_NETWORK": "等待网络...", + "CHECKING_NEW_VERSION": "检查新版本...", + "CHECK_NEW_VERSION_FAILED": "检查新版本失败,将在 %d 秒后重试:%s", + "SWITCH_TO_WIFI_NETWORK": "切换到 Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "切换到 4G...", + "STANDBY": "待命", + "CONNECT_TO": "连接 ", + "CONNECTING": "连接中...", + "CONNECTED_TO": "已连接 ", + "LISTENING": "聆听中...", + "SPEAKING": "说话中...", + "SERVER_NOT_FOUND": "正在寻找可用服务", + "SERVER_NOT_CONNECTED": "无法连接服务,请稍后再试", + "SERVER_TIMEOUT": "等待响应超时", + "SERVER_ERROR": "发送失败,请检查网络", + "CONNECT_TO_HOTSPOT": "手机连接热点 ", + "ACCESS_VIA_BROWSER": ",浏览器访问 ", + "WIFI_CONFIG_MODE": "配网模式", + "ENTERING_WIFI_CONFIG_MODE": "进入配网模式...", + "SCANNING_WIFI": "扫描 Wi-Fi...", + "NEW_VERSION": "新版本 ", + "OTA_UPGRADE": "OTA 升级", + "UPGRADING": "正在升级系统...", + "UPGRADE_FAILED": "升级失败", + "ACTIVATION": "激活设备", + "BATTERY_LOW": "电量不足", + "BATTERY_CHARGING": "正在充电", + "BATTERY_FULL": "电量已满", + "BATTERY_NEED_CHARGE": "电量低,请充电", + "VOLUME": "音量 ", + "MUTED": "已静音", + "MAX_VOLUME": "最大音量", + "RTC_MODE_OFF": "AEC 关闭", + "RTC_MODE_ON": "AEC 开启", + "DOWNLOAD_ASSETS_FAILED": "下载资源失败", + "LOADING_ASSETS": "加载资源...", + "PLEASE_WAIT": "请稍候...", + "FOUND_NEW_ASSETS": "发现新资源: %s", + "HELLO_MY_FRIEND": "你好,我的朋友!" + } +} \ No newline at end of file diff --git a/main/assets/locales/zh-CN/upgrade.ogg b/main/assets/locales/zh-CN/upgrade.ogg new file mode 100644 index 0000000..1feb87b Binary files /dev/null and b/main/assets/locales/zh-CN/upgrade.ogg differ diff --git a/main/assets/locales/zh-CN/welcome.ogg b/main/assets/locales/zh-CN/welcome.ogg new file mode 100644 index 0000000..b2eeb4f Binary files /dev/null and b/main/assets/locales/zh-CN/welcome.ogg differ diff --git a/main/assets/locales/zh-CN/wificonfig.ogg b/main/assets/locales/zh-CN/wificonfig.ogg new file mode 100644 index 0000000..7ef88e2 Binary files /dev/null and b/main/assets/locales/zh-CN/wificonfig.ogg differ diff --git a/main/assets/locales/zh-TW/0.ogg b/main/assets/locales/zh-TW/0.ogg new file mode 100644 index 0000000..0cb1247 Binary files /dev/null and b/main/assets/locales/zh-TW/0.ogg differ diff --git a/main/assets/locales/zh-TW/1.ogg b/main/assets/locales/zh-TW/1.ogg new file mode 100644 index 0000000..858af34 Binary files /dev/null and b/main/assets/locales/zh-TW/1.ogg differ diff --git a/main/assets/locales/zh-TW/2.ogg b/main/assets/locales/zh-TW/2.ogg new file mode 100644 index 0000000..72f53aa Binary files /dev/null and b/main/assets/locales/zh-TW/2.ogg differ diff --git a/main/assets/locales/zh-TW/3.ogg b/main/assets/locales/zh-TW/3.ogg new file mode 100644 index 0000000..848af11 Binary files /dev/null and b/main/assets/locales/zh-TW/3.ogg differ diff --git a/main/assets/locales/zh-TW/4.ogg b/main/assets/locales/zh-TW/4.ogg new file mode 100644 index 0000000..39b3eee Binary files /dev/null and b/main/assets/locales/zh-TW/4.ogg differ diff --git a/main/assets/locales/zh-TW/5.ogg b/main/assets/locales/zh-TW/5.ogg new file mode 100644 index 0000000..9230358 Binary files /dev/null and b/main/assets/locales/zh-TW/5.ogg differ diff --git a/main/assets/locales/zh-TW/6.ogg b/main/assets/locales/zh-TW/6.ogg new file mode 100644 index 0000000..9ecb574 Binary files /dev/null and b/main/assets/locales/zh-TW/6.ogg differ diff --git a/main/assets/locales/zh-TW/7.ogg b/main/assets/locales/zh-TW/7.ogg new file mode 100644 index 0000000..6348799 Binary files /dev/null and b/main/assets/locales/zh-TW/7.ogg differ diff --git a/main/assets/locales/zh-TW/8.ogg b/main/assets/locales/zh-TW/8.ogg new file mode 100644 index 0000000..67fc7a9 Binary files /dev/null and b/main/assets/locales/zh-TW/8.ogg differ diff --git a/main/assets/locales/zh-TW/9.ogg b/main/assets/locales/zh-TW/9.ogg new file mode 100644 index 0000000..a7769d9 Binary files /dev/null and b/main/assets/locales/zh-TW/9.ogg differ diff --git a/main/assets/locales/zh-TW/activation.ogg b/main/assets/locales/zh-TW/activation.ogg new file mode 100644 index 0000000..33291af Binary files /dev/null and b/main/assets/locales/zh-TW/activation.ogg differ diff --git a/main/assets/locales/zh-TW/err_pin.ogg b/main/assets/locales/zh-TW/err_pin.ogg new file mode 100644 index 0000000..e455244 Binary files /dev/null and b/main/assets/locales/zh-TW/err_pin.ogg differ diff --git a/main/assets/locales/zh-TW/err_reg.ogg b/main/assets/locales/zh-TW/err_reg.ogg new file mode 100644 index 0000000..a3456f1 Binary files /dev/null and b/main/assets/locales/zh-TW/err_reg.ogg differ diff --git a/main/assets/locales/zh-TW/language.json b/main/assets/locales/zh-TW/language.json new file mode 100644 index 0000000..f035b36 --- /dev/null +++ b/main/assets/locales/zh-TW/language.json @@ -0,0 +1,55 @@ +{ + "language": { + "type": "zh-TW" + }, + "strings": { + "WARNING": "警告", + "INFO": "資訊", + "ERROR": "錯誤", + "VERSION": "版本 ", + "LOADING_PROTOCOL": "登入伺服器...", + "INITIALIZING": "正在初始化...", + "PIN_ERROR": "請插入 SIM 卡", + "REG_ERROR": "無法接入網絡,請檢查網路狀態", + "DETECTING_MODULE": "檢測模組...", + "REGISTERING_NETWORK": "等待網絡...", + "CHECKING_NEW_VERSION": "檢查新版本...", + "CHECK_NEW_VERSION_FAILED": "檢查新版本失敗,將在 %d 秒後重試:%s", + "SWITCH_TO_WIFI_NETWORK": "切換到 Wi-Fi...", + "SWITCH_TO_4G_NETWORK": "切換到 4G...", + "STANDBY": "待命", + "CONNECT_TO": "連接 ", + "CONNECTING": "連接中...", + "CONNECTED_TO": "已連接 ", + "LISTENING": "聆聽中...", + "SPEAKING": "說話中...", + "SERVER_NOT_FOUND": "正在尋找可用服務", + "SERVER_NOT_CONNECTED": "無法連接服務,請稍後再試", + "SERVER_TIMEOUT": "等待響應超時", + "SERVER_ERROR": "發送失敗,請檢查網絡", + "CONNECT_TO_HOTSPOT": "手機連接WiFi ", + "ACCESS_VIA_BROWSER": ",瀏覽器訪問 ", + "WIFI_CONFIG_MODE": "網路設定模式", + "ENTERING_WIFI_CONFIG_MODE": "正在設定網路...", + "SCANNING_WIFI": "掃描 Wi-Fi...", + "NEW_VERSION": "新版本 ", + "OTA_UPGRADE": "OTA 升級", + "UPGRADING": "正在升級系統...", + "UPGRADE_FAILED": "升級失敗", + "ACTIVATION": "啟用設備", + "BATTERY_LOW": "電量不足", + "BATTERY_CHARGING": "正在充電", + "BATTERY_FULL": "電量已滿", + "BATTERY_NEED_CHARGE": "電量低,請充電", + "VOLUME": "音量 ", + "MUTED": "已靜音", + "MAX_VOLUME": "最大音量", + "RTC_MODE_OFF": "AEC 關閉", + "RTC_MODE_ON": "AEC 開啟", + "DOWNLOAD_ASSETS_FAILED": "下載資源失敗", + "LOADING_ASSETS": "載入資源...", + "PLEASE_WAIT": "請稍候...", + "FOUND_NEW_ASSETS": "發現新資源: %s", + "HELLO_MY_FRIEND": "你好,我的朋友!" + } +} \ No newline at end of file diff --git a/main/assets/locales/zh-TW/upgrade.ogg b/main/assets/locales/zh-TW/upgrade.ogg new file mode 100644 index 0000000..1feb87b Binary files /dev/null and b/main/assets/locales/zh-TW/upgrade.ogg differ diff --git a/main/assets/locales/zh-TW/welcome.ogg b/main/assets/locales/zh-TW/welcome.ogg new file mode 100644 index 0000000..b2eeb4f Binary files /dev/null and b/main/assets/locales/zh-TW/welcome.ogg differ diff --git a/main/assets/locales/zh-TW/wificonfig.ogg b/main/assets/locales/zh-TW/wificonfig.ogg new file mode 100644 index 0000000..7ef88e2 Binary files /dev/null and b/main/assets/locales/zh-TW/wificonfig.ogg differ diff --git a/main/audio/README.md b/main/audio/README.md new file mode 100644 index 0000000..6159f9a --- /dev/null +++ b/main/audio/README.md @@ -0,0 +1,88 @@ +# Audio Service Architecture + +The audio service is a core component responsible for managing all audio-related functionalities, including capturing audio from the microphone, processing it, encoding/decoding, and playing back audio through the speaker. It is designed to be modular and efficient, running its main operations in dedicated FreeRTOS tasks to ensure real-time performance. + +## Key Components + +- **`AudioService`**: The central orchestrator. It initializes and manages all other audio components, tasks, and data queues. +- **`AudioCodec`**: A hardware abstraction layer (HAL) for the physical audio codec chip. It handles the raw I2S communication for audio input and output. +- **`AudioProcessor`**: Performs real-time audio processing on the microphone input stream. This typically includes Acoustic Echo Cancellation (AEC), noise suppression, and Voice Activity Detection (VAD). `AfeAudioProcessor` is the default implementation, utilizing the ESP-ADF Audio Front-End. +- **`WakeWord`**: Detects keywords (e.g., "你好,小智", "Hi, ESP") from the audio stream. It runs independently from the main audio processor until a wake word is detected. +- **`OpusEncoderWrapper` / `OpusDecoderWrapper`**: Manages the encoding of PCM audio to the Opus format and decoding Opus packets back to PCM. Opus is used for its high compression and low latency, making it ideal for voice streaming. +- **`OpusResampler`**: A utility to convert audio streams between different sample rates (e.g., resampling from the codec's native sample rate to the required 16kHz for processing). + +## Threading Model + +The service operates on three primary tasks to handle the different stages of the audio pipeline concurrently: + +1. **`AudioInputTask`**: Solely responsible for reading raw PCM data from the `AudioCodec`. It then feeds this data to either the `WakeWord` engine or the `AudioProcessor` based on the current state. +2. **`AudioOutputTask`**: Responsible for playing audio. It retrieves decoded PCM data from the `audio_playback_queue_` and sends it to the `AudioCodec` to be played on the speaker. +3. **`OpusCodecTask`**: A worker task that handles both encoding and decoding. It fetches raw audio from `audio_encode_queue_`, encodes it into Opus packets, and places them in the `audio_send_queue_`. Concurrently, it fetches Opus packets from `audio_decode_queue_`, decodes them into PCM, and places the result in the `audio_playback_queue_`. + +## Data Flow + +There are two primary data flows: audio input (uplink) and audio output (downlink). + +### 1. Audio Input (Uplink) Flow + +This flow captures audio from the microphone, processes it, encodes it, and prepares it for sending to a server. + +```mermaid +graph TD + subgraph Device + Mic[("Microphone")] -->|I2S| Codec(AudioCodec) + + subgraph AudioInputTask + Codec -->|Raw PCM| Read(ReadAudioData) + Read -->|16kHz PCM| Processor(AudioProcessor) + end + + subgraph OpusCodecTask + Processor -->|Clean PCM| EncodeQueue(audio_encode_queue_) + EncodeQueue --> Encoder(OpusEncoder) + Encoder -->|Opus Packet| SendQueue(audio_send_queue_) + end + + SendQueue --> |"PopPacketFromSendQueue()"| App(Application Layer) + end + + App -->|Network| Server((Cloud Server)) +``` + +- The `AudioInputTask` continuously reads raw PCM data from the `AudioCodec`. +- This data is fed into an `AudioProcessor` for cleaning (AEC, VAD). +- The processed PCM data is pushed into the `audio_encode_queue_`. +- The `OpusCodecTask` picks up the PCM data, encodes it into Opus format, and pushes the resulting packet to the `audio_send_queue_`. +- The application can then retrieve these Opus packets and send them over the network. + +### 2. Audio Output (Downlink) Flow + +This flow receives encoded audio data, decodes it, and plays it on the speaker. + +```mermaid +graph TD + Server((Cloud Server)) -->|Network| App(Application Layer) + + subgraph Device + App -->|"PushPacketToDecodeQueue()"| DecodeQueue(audio_decode_queue_) + + subgraph OpusCodecTask + DecodeQueue -->|Opus Packet| Decoder(OpusDecoder) + Decoder -->|PCM| PlaybackQueue(audio_playback_queue_) + end + + subgraph AudioOutputTask + PlaybackQueue -->|PCM| Codec(AudioCodec) + end + + Codec -->|I2S| Speaker[("Speaker")] + end +``` + +- The application receives Opus packets from the network and pushes them into the `audio_decode_queue_`. +- The `OpusCodecTask` retrieves these packets, decodes them back into PCM data, and pushes the data to the `audio_playback_queue_`. +- The `AudioOutputTask` takes the PCM data from the queue and sends it to the `AudioCodec` for playback. + +## Power Management + +To conserve energy, the audio codec's input (ADC) and output (DAC) channels are automatically disabled after a period of inactivity (`AUDIO_POWER_TIMEOUT_MS`). A timer (`audio_power_timer_`) periodically checks for activity and manages the power state. The channels are automatically re-enabled when new audio needs to be captured or played. \ No newline at end of file diff --git a/main/audio/audio_codec.cc b/main/audio/audio_codec.cc new file mode 100644 index 0000000..055cd82 --- /dev/null +++ b/main/audio/audio_codec.cc @@ -0,0 +1,77 @@ +#include "audio_codec.h" +#include "board.h" +#include "settings.h" + +#include +#include +#include + +#define TAG "AudioCodec" + +AudioCodec::AudioCodec() { +} + +AudioCodec::~AudioCodec() { +} + +void AudioCodec::OutputData(std::vector& data) { + Write(data.data(), data.size()); +} + +bool AudioCodec::InputData(std::vector& data) { + int samples = Read(data.data(), data.size()); + if (samples > 0) { + return true; + } + return false; +} + +void AudioCodec::Start() { + Settings settings("audio", false); + output_volume_ = settings.GetInt("output_volume", output_volume_); + if (output_volume_ <= 0) { + ESP_LOGW(TAG, "Output volume value (%d) is too small, setting to default (10)", output_volume_); + output_volume_ = 10; + } + + if (tx_handle_ != nullptr) { + ESP_ERROR_CHECK(i2s_channel_enable(tx_handle_)); + } + + if (rx_handle_ != nullptr) { + ESP_ERROR_CHECK(i2s_channel_enable(rx_handle_)); + } + + EnableInput(true); + EnableOutput(true); + ESP_LOGI(TAG, "Audio codec started"); +} + +void AudioCodec::SetOutputVolume(int volume) { + output_volume_ = volume; + ESP_LOGI(TAG, "Set output volume to %d", output_volume_); + + Settings settings("audio", true); + settings.SetInt("output_volume", output_volume_); +} + +void AudioCodec::SetInputGain(float gain) { + input_gain_ = gain; + ESP_LOGI(TAG, "Set input gain to %.1f", input_gain_); +} + +void AudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + input_enabled_ = enable; + ESP_LOGI(TAG, "Set input enable to %s", enable ? "true" : "false"); +} + +void AudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + output_enabled_ = enable; + ESP_LOGI(TAG, "Set output enable to %s", enable ? "true" : "false"); +} diff --git a/main/audio/audio_codec.h b/main/audio/audio_codec.h new file mode 100644 index 0000000..819e646 --- /dev/null +++ b/main/audio/audio_codec.h @@ -0,0 +1,61 @@ +#ifndef _AUDIO_CODEC_H +#define _AUDIO_CODEC_H + +#include +#include +#include + +#include +#include +#include + +#include "board.h" + +#define AUDIO_CODEC_DMA_DESC_NUM 6 +#define AUDIO_CODEC_DMA_FRAME_NUM 240 + +class AudioCodec { +public: + AudioCodec(); + virtual ~AudioCodec(); + + virtual void SetOutputVolume(int volume); + virtual void SetInputGain(float gain); + virtual void EnableInput(bool enable); + virtual void EnableOutput(bool enable); + + virtual void OutputData(std::vector& data); + virtual bool InputData(std::vector& data); + virtual void Start(); + + inline bool duplex() const { return duplex_; } + inline bool input_reference() const { return input_reference_; } + inline int input_sample_rate() const { return input_sample_rate_; } + inline int output_sample_rate() const { return output_sample_rate_; } + inline int input_channels() const { return input_channels_; } + inline int output_channels() const { return output_channels_; } + inline int output_volume() const { return output_volume_; } + inline float input_gain() const { return input_gain_; } + inline bool input_enabled() const { return input_enabled_; } + inline bool output_enabled() const { return output_enabled_; } + +protected: + i2s_chan_handle_t tx_handle_ = nullptr; + i2s_chan_handle_t rx_handle_ = nullptr; + + bool duplex_ = false; + bool input_reference_ = false; + bool input_enabled_ = false; + bool output_enabled_ = false; + int input_sample_rate_ = 0; + int output_sample_rate_ = 0; + int input_channels_ = 1; + int output_channels_ = 1; + int output_volume_ = 70; + float input_gain_ = 0.0; + + virtual int Read(int16_t* dest, int samples) = 0; + virtual int Write(const int16_t* data, int samples) = 0; +}; + +#endif // _AUDIO_CODEC_H diff --git a/main/audio/audio_processor.h b/main/audio/audio_processor.h new file mode 100644 index 0000000..543c7ae --- /dev/null +++ b/main/audio/audio_processor.h @@ -0,0 +1,26 @@ +#ifndef AUDIO_PROCESSOR_H +#define AUDIO_PROCESSOR_H + +#include +#include +#include + +#include +#include "audio_codec.h" + +class AudioProcessor { +public: + virtual ~AudioProcessor() = default; + + virtual void Initialize(AudioCodec* codec, int frame_duration_ms, srmodel_list_t* models_list) = 0; + virtual void Feed(std::vector&& data) = 0; + virtual void Start() = 0; + virtual void Stop() = 0; + virtual bool IsRunning() = 0; + virtual void OnOutput(std::function&& data)> callback) = 0; + virtual void OnVadStateChange(std::function callback) = 0; + virtual size_t GetFeedSize() = 0; + virtual void EnableDeviceAec(bool enable) = 0; +}; + +#endif diff --git a/main/audio/audio_service.cc b/main/audio/audio_service.cc new file mode 100644 index 0000000..c5d3ed7 --- /dev/null +++ b/main/audio/audio_service.cc @@ -0,0 +1,686 @@ +#include "audio_service.h" +#include +#include + +#if CONFIG_USE_AUDIO_PROCESSOR +#include "processors/afe_audio_processor.h" +#else +#include "processors/no_audio_processor.h" +#endif + +#if CONFIG_IDF_TARGET_ESP32S3 || CONFIG_IDF_TARGET_ESP32P4 +#include "wake_words/afe_wake_word.h" +#include "wake_words/custom_wake_word.h" +#else +#include "wake_words/esp_wake_word.h" +#endif + +#define TAG "AudioService" + + +AudioService::AudioService() { + event_group_ = xEventGroupCreate(); +} + +AudioService::~AudioService() { + if (event_group_ != nullptr) { + vEventGroupDelete(event_group_); + } +} + + +void AudioService::Initialize(AudioCodec* codec) { + codec_ = codec; + codec_->Start(); + + /* Setup the audio codec */ + opus_decoder_ = std::make_unique(codec->output_sample_rate(), 1, OPUS_FRAME_DURATION_MS); + opus_encoder_ = std::make_unique(16000, 1, OPUS_FRAME_DURATION_MS); + opus_encoder_->SetComplexity(0); + + if (codec->input_sample_rate() != 16000) { + input_resampler_.Configure(codec->input_sample_rate(), 16000); + reference_resampler_.Configure(codec->input_sample_rate(), 16000); + } + +#if CONFIG_USE_AUDIO_PROCESSOR + audio_processor_ = std::make_unique(); +#else + audio_processor_ = std::make_unique(); +#endif + + audio_processor_->OnOutput([this](std::vector&& data) { + PushTaskToEncodeQueue(kAudioTaskTypeEncodeToSendQueue, std::move(data)); + }); + + audio_processor_->OnVadStateChange([this](bool speaking) { + voice_detected_ = speaking; + if (callbacks_.on_vad_change) { + callbacks_.on_vad_change(speaking); + } + }); + + esp_timer_create_args_t audio_power_timer_args = { + .callback = [](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->CheckAndUpdateAudioPowerState(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "audio_power_timer", + .skip_unhandled_events = true, + }; + esp_timer_create(&audio_power_timer_args, &audio_power_timer_); +} + +void AudioService::Start() { + service_stopped_ = false; + xEventGroupClearBits(event_group_, AS_EVENT_AUDIO_TESTING_RUNNING | AS_EVENT_WAKE_WORD_RUNNING | AS_EVENT_AUDIO_PROCESSOR_RUNNING); + + esp_timer_start_periodic(audio_power_timer_, 1000000); + +#if CONFIG_USE_AUDIO_PROCESSOR + /* Start the audio input task */ + xTaskCreatePinnedToCore([](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->AudioInputTask(); + vTaskDelete(NULL); + }, "audio_input", 2048 * 3, this, 8, &audio_input_task_handle_, 0); + + /* Start the audio output task */ + xTaskCreate([](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->AudioOutputTask(); + vTaskDelete(NULL); + }, "audio_output", 2048 * 2, this, 4, &audio_output_task_handle_); +#else + /* Start the audio input task */ + xTaskCreate([](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->AudioInputTask(); + vTaskDelete(NULL); + }, "audio_input", 2048 * 2, this, 8, &audio_input_task_handle_); + + /* Start the audio output task */ + xTaskCreate([](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->AudioOutputTask(); + vTaskDelete(NULL); + }, "audio_output", 2048, this, 4, &audio_output_task_handle_); +#endif + + /* Start the opus codec task */ + xTaskCreate([](void* arg) { + AudioService* audio_service = (AudioService*)arg; + audio_service->OpusCodecTask(); + vTaskDelete(NULL); + }, "opus_codec", 2048 * 13, this, 2, &opus_codec_task_handle_); +} + +void AudioService::Stop() { + esp_timer_stop(audio_power_timer_); + service_stopped_ = true; + xEventGroupSetBits(event_group_, AS_EVENT_AUDIO_TESTING_RUNNING | + AS_EVENT_WAKE_WORD_RUNNING | + AS_EVENT_AUDIO_PROCESSOR_RUNNING); + + std::lock_guard lock(audio_queue_mutex_); + audio_encode_queue_.clear(); + audio_decode_queue_.clear(); + audio_playback_queue_.clear(); + audio_testing_queue_.clear(); + audio_queue_cv_.notify_all(); +} + +bool AudioService::ReadAudioData(std::vector& data, int sample_rate, int samples) { + if (!codec_->input_enabled()) { + esp_timer_stop(audio_power_timer_); + esp_timer_start_periodic(audio_power_timer_, AUDIO_POWER_CHECK_INTERVAL_MS * 1000); + codec_->EnableInput(true); + } + + if (codec_->input_sample_rate() != sample_rate) { + data.resize(samples * codec_->input_sample_rate() / sample_rate * codec_->input_channels()); + if (!codec_->InputData(data)) { + return false; + } + if (codec_->input_channels() == 2) { + auto mic_channel = std::vector(data.size() / 2); + auto reference_channel = std::vector(data.size() / 2); + for (size_t i = 0, j = 0; i < mic_channel.size(); ++i, j += 2) { + mic_channel[i] = data[j]; + reference_channel[i] = data[j + 1]; + } + auto resampled_mic = std::vector(input_resampler_.GetOutputSamples(mic_channel.size())); + auto resampled_reference = std::vector(reference_resampler_.GetOutputSamples(reference_channel.size())); + input_resampler_.Process(mic_channel.data(), mic_channel.size(), resampled_mic.data()); + reference_resampler_.Process(reference_channel.data(), reference_channel.size(), resampled_reference.data()); + data.resize(resampled_mic.size() + resampled_reference.size()); + for (size_t i = 0, j = 0; i < resampled_mic.size(); ++i, j += 2) { + data[j] = resampled_mic[i]; + data[j + 1] = resampled_reference[i]; + } + } else { + auto resampled = std::vector(input_resampler_.GetOutputSamples(data.size())); + input_resampler_.Process(data.data(), data.size(), resampled.data()); + data = std::move(resampled); + } + } else { + data.resize(samples * codec_->input_channels()); + if (!codec_->InputData(data)) { + return false; + } + } + + /* Update the last input time */ + last_input_time_ = std::chrono::steady_clock::now(); + debug_statistics_.input_count++; + +#if CONFIG_USE_AUDIO_DEBUGGER + // 音频调试:发送原始音频数据 + if (audio_debugger_ == nullptr) { + audio_debugger_ = std::make_unique(); + } + audio_debugger_->Feed(data); +#endif + + return true; +} + +void AudioService::AudioInputTask() { + while (true) { + EventBits_t bits = xEventGroupWaitBits(event_group_, AS_EVENT_AUDIO_TESTING_RUNNING | + AS_EVENT_WAKE_WORD_RUNNING | AS_EVENT_AUDIO_PROCESSOR_RUNNING, + pdFALSE, pdFALSE, portMAX_DELAY); + + if (service_stopped_) { + break; + } + if (audio_input_need_warmup_) { + audio_input_need_warmup_ = false; + vTaskDelay(pdMS_TO_TICKS(120)); + continue; + } + + /* Used for audio testing in NetworkConfiguring mode by clicking the BOOT button */ + if (bits & AS_EVENT_AUDIO_TESTING_RUNNING) { + if (audio_testing_queue_.size() >= AUDIO_TESTING_MAX_DURATION_MS / OPUS_FRAME_DURATION_MS) { + ESP_LOGW(TAG, "Audio testing queue is full, stopping audio testing"); + EnableAudioTesting(false); + continue; + } + std::vector data; + int samples = OPUS_FRAME_DURATION_MS * 16000 / 1000; + if (ReadAudioData(data, 16000, samples)) { + // If input channels is 2, we need to fetch the left channel data + if (codec_->input_channels() == 2) { + auto mono_data = std::vector(data.size() / 2); + for (size_t i = 0, j = 0; i < mono_data.size(); ++i, j += 2) { + mono_data[i] = data[j]; + } + data = std::move(mono_data); + } + PushTaskToEncodeQueue(kAudioTaskTypeEncodeToTestingQueue, std::move(data)); + continue; + } + } + + /* Feed the wake word */ + if (bits & AS_EVENT_WAKE_WORD_RUNNING) { + std::vector data; + int samples = wake_word_->GetFeedSize(); + if (samples > 0) { + if (ReadAudioData(data, 16000, samples)) { + wake_word_->Feed(data); + continue; + } + } + } + + /* Feed the audio processor */ + if (bits & AS_EVENT_AUDIO_PROCESSOR_RUNNING) { + std::vector data; + int samples = audio_processor_->GetFeedSize(); + if (samples > 0) { + if (ReadAudioData(data, 16000, samples)) { + audio_processor_->Feed(std::move(data)); + continue; + } + } + } + + ESP_LOGE(TAG, "Should not be here, bits: %lx", bits); + break; + } + + ESP_LOGW(TAG, "Audio input task stopped"); +} + +void AudioService::AudioOutputTask() { + while (true) { + std::unique_lock lock(audio_queue_mutex_); + audio_queue_cv_.wait(lock, [this]() { return !audio_playback_queue_.empty() || service_stopped_; }); + if (service_stopped_) { + break; + } + + auto task = std::move(audio_playback_queue_.front()); + audio_playback_queue_.pop_front(); + audio_queue_cv_.notify_all(); + lock.unlock(); + + if (!codec_->output_enabled()) { + esp_timer_stop(audio_power_timer_); + esp_timer_start_periodic(audio_power_timer_, AUDIO_POWER_CHECK_INTERVAL_MS * 1000); + codec_->EnableOutput(true); + } + codec_->OutputData(task->pcm); + + /* Update the last output time */ + last_output_time_ = std::chrono::steady_clock::now(); + debug_statistics_.playback_count++; + +#if CONFIG_USE_SERVER_AEC + /* Record the timestamp for server AEC */ + if (task->timestamp > 0) { + lock.lock(); + timestamp_queue_.push_back(task->timestamp); + } +#endif + } + + ESP_LOGW(TAG, "Audio output task stopped"); +} + +void AudioService::OpusCodecTask() { + while (true) { + std::unique_lock lock(audio_queue_mutex_); + audio_queue_cv_.wait(lock, [this]() { + return service_stopped_ || + (!audio_encode_queue_.empty() && audio_send_queue_.size() < MAX_SEND_PACKETS_IN_QUEUE) || + (!audio_decode_queue_.empty() && audio_playback_queue_.size() < MAX_PLAYBACK_TASKS_IN_QUEUE); + }); + if (service_stopped_) { + break; + } + + /* Decode the audio from decode queue */ + if (!audio_decode_queue_.empty() && audio_playback_queue_.size() < MAX_PLAYBACK_TASKS_IN_QUEUE) { + auto packet = std::move(audio_decode_queue_.front()); + audio_decode_queue_.pop_front(); + audio_queue_cv_.notify_all(); + lock.unlock(); + + auto task = std::make_unique(); + task->type = kAudioTaskTypeDecodeToPlaybackQueue; + task->timestamp = packet->timestamp; + + SetDecodeSampleRate(packet->sample_rate, packet->frame_duration); + if (opus_decoder_->Decode(std::move(packet->payload), task->pcm)) { + // Resample if the sample rate is different + if (opus_decoder_->sample_rate() != codec_->output_sample_rate()) { + int target_size = output_resampler_.GetOutputSamples(task->pcm.size()); + std::vector resampled(target_size); + output_resampler_.Process(task->pcm.data(), task->pcm.size(), resampled.data()); + task->pcm = std::move(resampled); + } + + lock.lock(); + audio_playback_queue_.push_back(std::move(task)); + audio_queue_cv_.notify_all(); + } else { + ESP_LOGE(TAG, "Failed to decode audio"); + lock.lock(); + } + debug_statistics_.decode_count++; + } + + /* Encode the audio to send queue */ + if (!audio_encode_queue_.empty() && audio_send_queue_.size() < MAX_SEND_PACKETS_IN_QUEUE) { + auto task = std::move(audio_encode_queue_.front()); + audio_encode_queue_.pop_front(); + audio_queue_cv_.notify_all(); + lock.unlock(); + + auto packet = std::make_unique(); + packet->frame_duration = OPUS_FRAME_DURATION_MS; + packet->sample_rate = 16000; + packet->timestamp = task->timestamp; + if (!opus_encoder_->Encode(std::move(task->pcm), packet->payload)) { + ESP_LOGE(TAG, "Failed to encode audio"); + continue; + } + + if (task->type == kAudioTaskTypeEncodeToSendQueue) { + { + std::lock_guard lock(audio_queue_mutex_); + audio_send_queue_.push_back(std::move(packet)); + } + if (callbacks_.on_send_queue_available) { + callbacks_.on_send_queue_available(); + } + } else if (task->type == kAudioTaskTypeEncodeToTestingQueue) { + std::lock_guard lock(audio_queue_mutex_); + audio_testing_queue_.push_back(std::move(packet)); + } + debug_statistics_.encode_count++; + lock.lock(); + } + } + + ESP_LOGW(TAG, "Opus codec task stopped"); +} + +void AudioService::SetDecodeSampleRate(int sample_rate, int frame_duration) { + if (opus_decoder_->sample_rate() == sample_rate && opus_decoder_->duration_ms() == frame_duration) { + return; + } + + opus_decoder_.reset(); + opus_decoder_ = std::make_unique(sample_rate, 1, frame_duration); + + auto codec = Board::GetInstance().GetAudioCodec(); + if (opus_decoder_->sample_rate() != codec->output_sample_rate()) { + ESP_LOGI(TAG, "Resampling audio from %d to %d", opus_decoder_->sample_rate(), codec->output_sample_rate()); + output_resampler_.Configure(opus_decoder_->sample_rate(), codec->output_sample_rate()); + } +} + +void AudioService::PushTaskToEncodeQueue(AudioTaskType type, std::vector&& pcm) { + auto task = std::make_unique(); + task->type = type; + task->pcm = std::move(pcm); + + /* Push the task to the encode queue */ + std::unique_lock lock(audio_queue_mutex_); + + /* If the task is to send queue, we need to set the timestamp */ + if (type == kAudioTaskTypeEncodeToSendQueue && !timestamp_queue_.empty()) { + if (timestamp_queue_.size() <= MAX_TIMESTAMPS_IN_QUEUE) { + task->timestamp = timestamp_queue_.front(); + } else { + ESP_LOGW(TAG, "Timestamp queue (%u) is full, dropping timestamp", timestamp_queue_.size()); + } + timestamp_queue_.pop_front(); + } + + audio_queue_cv_.wait(lock, [this]() { return audio_encode_queue_.size() < MAX_ENCODE_TASKS_IN_QUEUE; }); + audio_encode_queue_.push_back(std::move(task)); + audio_queue_cv_.notify_all(); +} + +bool AudioService::PushPacketToDecodeQueue(std::unique_ptr packet, bool wait) { + std::unique_lock lock(audio_queue_mutex_); + if (audio_decode_queue_.size() >= MAX_DECODE_PACKETS_IN_QUEUE) { + if (wait) { + audio_queue_cv_.wait(lock, [this]() { return audio_decode_queue_.size() < MAX_DECODE_PACKETS_IN_QUEUE; }); + } else { + return false; + } + } + audio_decode_queue_.push_back(std::move(packet)); + audio_queue_cv_.notify_all(); + return true; +} + +std::unique_ptr AudioService::PopPacketFromSendQueue() { + std::lock_guard lock(audio_queue_mutex_); + if (audio_send_queue_.empty()) { + return nullptr; + } + auto packet = std::move(audio_send_queue_.front()); + audio_send_queue_.pop_front(); + audio_queue_cv_.notify_all(); + return packet; +} + +void AudioService::EncodeWakeWord() { + if (wake_word_) { + wake_word_->EncodeWakeWordData(); + } +} + +const std::string& AudioService::GetLastWakeWord() const { + return wake_word_->GetLastDetectedWakeWord(); +} + +std::unique_ptr AudioService::PopWakeWordPacket() { + auto packet = std::make_unique(); + if (wake_word_->GetWakeWordOpus(packet->payload)) { + return packet; + } + return nullptr; +} + +void AudioService::EnableWakeWordDetection(bool enable) { + if (!wake_word_) { + return; + } + + ESP_LOGD(TAG, "%s wake word detection", enable ? "Enabling" : "Disabling"); + if (enable) { + if (!wake_word_initialized_) { + if (!wake_word_->Initialize(codec_, models_list_)) { + ESP_LOGE(TAG, "Failed to initialize wake word"); + return; + } + wake_word_initialized_ = true; + } + wake_word_->Start(); + xEventGroupSetBits(event_group_, AS_EVENT_WAKE_WORD_RUNNING); + } else { + wake_word_->Stop(); + xEventGroupClearBits(event_group_, AS_EVENT_WAKE_WORD_RUNNING); + } +} + +void AudioService::EnableVoiceProcessing(bool enable) { + ESP_LOGD(TAG, "%s voice processing", enable ? "Enabling" : "Disabling"); + if (enable) { + if (!audio_processor_initialized_) { + audio_processor_->Initialize(codec_, OPUS_FRAME_DURATION_MS, models_list_); + audio_processor_initialized_ = true; + } + + /* We should make sure no audio is playing */ + ResetDecoder(); + audio_input_need_warmup_ = true; + audio_processor_->Start(); + xEventGroupSetBits(event_group_, AS_EVENT_AUDIO_PROCESSOR_RUNNING); + } else { + audio_processor_->Stop(); + xEventGroupClearBits(event_group_, AS_EVENT_AUDIO_PROCESSOR_RUNNING); + } +} + +void AudioService::EnableAudioTesting(bool enable) { + ESP_LOGI(TAG, "%s audio testing", enable ? "Enabling" : "Disabling"); + if (enable) { + xEventGroupSetBits(event_group_, AS_EVENT_AUDIO_TESTING_RUNNING); + } else { + xEventGroupClearBits(event_group_, AS_EVENT_AUDIO_TESTING_RUNNING); + /* Copy audio_testing_queue_ to audio_decode_queue_ */ + std::lock_guard lock(audio_queue_mutex_); + audio_decode_queue_ = std::move(audio_testing_queue_); + audio_queue_cv_.notify_all(); + } +} + +void AudioService::EnableDeviceAec(bool enable) { + ESP_LOGI(TAG, "%s device AEC", enable ? "Enabling" : "Disabling"); + if (!audio_processor_initialized_) { + audio_processor_->Initialize(codec_, OPUS_FRAME_DURATION_MS, models_list_); + audio_processor_initialized_ = true; + } + + audio_processor_->EnableDeviceAec(enable); +} + +void AudioService::SetCallbacks(AudioServiceCallbacks& callbacks) { + callbacks_ = callbacks; +} + +void AudioService::PlaySound(const std::string_view& ogg) { + if (!codec_->output_enabled()) { + esp_timer_stop(audio_power_timer_); + esp_timer_start_periodic(audio_power_timer_, AUDIO_POWER_CHECK_INTERVAL_MS * 1000); + codec_->EnableOutput(true); + } + + const uint8_t* buf = reinterpret_cast(ogg.data()); + size_t size = ogg.size(); + size_t offset = 0; + + auto find_page = [&](size_t start)->size_t { + for (size_t i = start; i + 4 <= size; ++i) { + if (buf[i] == 'O' && buf[i+1] == 'g' && buf[i+2] == 'g' && buf[i+3] == 'S') return i; + } + return static_cast(-1); + }; + + bool seen_head = false; + bool seen_tags = false; + int sample_rate = 16000; // 默认值 + + while (true) { + size_t pos = find_page(offset); + if (pos == static_cast(-1)) break; + offset = pos; + if (offset + 27 > size) break; + + const uint8_t* page = buf + offset; + uint8_t page_segments = page[26]; + size_t seg_table_off = offset + 27; + if (seg_table_off + page_segments > size) break; + + size_t body_size = 0; + for (size_t i = 0; i < page_segments; ++i) body_size += page[27 + i]; + + size_t body_off = seg_table_off + page_segments; + if (body_off + body_size > size) break; + + // Parse packets using lacing + size_t cur = body_off; + size_t seg_idx = 0; + while (seg_idx < page_segments) { + size_t pkt_len = 0; + size_t pkt_start = cur; + bool continued = false; + do { + uint8_t l = page[27 + seg_idx++]; + pkt_len += l; + cur += l; + continued = (l == 255); + } while (continued && seg_idx < page_segments); + + if (pkt_len == 0) continue; + const uint8_t* pkt_ptr = buf + pkt_start; + + if (!seen_head) { + // 解析OpusHead包 + if (pkt_len >= 19 && std::memcmp(pkt_ptr, "OpusHead", 8) == 0) { + seen_head = true; + + // OpusHead结构:[0-7] "OpusHead", [8] version, [9] channel_count, [10-11] pre_skip + // [12-15] input_sample_rate, [16-17] output_gain, [18] mapping_family + if (pkt_len >= 12) { + uint8_t version = pkt_ptr[8]; + uint8_t channel_count = pkt_ptr[9]; + + if (pkt_len >= 16) { + // 读取输入采样率 (little-endian) + sample_rate = pkt_ptr[12] | (pkt_ptr[13] << 8) | + (pkt_ptr[14] << 16) | (pkt_ptr[15] << 24); + ESP_LOGI(TAG, "OpusHead: version=%d, channels=%d, sample_rate=%d", + version, channel_count, sample_rate); + } + } + } + continue; + } + if (!seen_tags) { + // Expect OpusTags in second packet + if (pkt_len >= 8 && std::memcmp(pkt_ptr, "OpusTags", 8) == 0) { + seen_tags = true; + } + continue; + } + + // Audio packet (Opus) + auto packet = std::make_unique(); + packet->sample_rate = sample_rate; + packet->frame_duration = 60; + packet->payload.resize(pkt_len); + std::memcpy(packet->payload.data(), pkt_ptr, pkt_len); + PushPacketToDecodeQueue(std::move(packet), true); + } + + offset = body_off + body_size; + } +} + +bool AudioService::IsIdle() { + std::lock_guard lock(audio_queue_mutex_); + return audio_encode_queue_.empty() && audio_decode_queue_.empty() && audio_playback_queue_.empty() && audio_testing_queue_.empty(); +} + +void AudioService::ResetDecoder() { + std::lock_guard lock(audio_queue_mutex_); + opus_decoder_->ResetState(); + timestamp_queue_.clear(); + audio_decode_queue_.clear(); + audio_playback_queue_.clear(); + audio_testing_queue_.clear(); + audio_queue_cv_.notify_all(); +} + +void AudioService::CheckAndUpdateAudioPowerState() { + auto now = std::chrono::steady_clock::now(); + auto input_elapsed = std::chrono::duration_cast(now - last_input_time_).count(); + auto output_elapsed = std::chrono::duration_cast(now - last_output_time_).count(); + if (input_elapsed > AUDIO_POWER_TIMEOUT_MS && codec_->input_enabled()) { + codec_->EnableInput(false); + } + if (output_elapsed > AUDIO_POWER_TIMEOUT_MS && codec_->output_enabled()) { + codec_->EnableOutput(false); + } + if (!codec_->input_enabled() && !codec_->output_enabled()) { + esp_timer_stop(audio_power_timer_); + } +} + +void AudioService::SetModelsList(srmodel_list_t* models_list) { + models_list_ = models_list; + +#if CONFIG_IDF_TARGET_ESP32S3 || CONFIG_IDF_TARGET_ESP32P4 + if (esp_srmodel_filter(models_list_, ESP_MN_PREFIX, NULL) != nullptr) { + wake_word_ = std::make_unique(); + } else if (esp_srmodel_filter(models_list_, ESP_WN_PREFIX, NULL) != nullptr) { + wake_word_ = std::make_unique(); + } else { + wake_word_ = nullptr; + } +#else + if (esp_srmodel_filter(models_list_, ESP_WN_PREFIX, NULL) != nullptr) { + wake_word_ = std::make_unique(); + } else { + wake_word_ = nullptr; + } +#endif + + if (wake_word_) { + wake_word_->OnWakeWordDetected([this](const std::string& wake_word) { + if (callbacks_.on_wake_word_detected) { + callbacks_.on_wake_word_detected(wake_word); + } + }); + } +} + +bool AudioService::IsAfeWakeWord() { +#if CONFIG_IDF_TARGET_ESP32S3 || CONFIG_IDF_TARGET_ESP32P4 + return wake_word_ != nullptr && dynamic_cast(wake_word_.get()) != nullptr; +#else + return false; +#endif +} diff --git a/main/audio/audio_service.h b/main/audio/audio_service.h new file mode 100644 index 0000000..c780806 --- /dev/null +++ b/main/audio/audio_service.h @@ -0,0 +1,161 @@ +#ifndef AUDIO_SERVICE_H +#define AUDIO_SERVICE_H + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "audio_codec.h" +#include "audio_processor.h" +#include "processors/audio_debugger.h" +#include "wake_word.h" +#include "protocol.h" + + +/* + * There are two types of audio data flow: + * 1. (MIC) -> [Processors] -> {Encode Queue} -> [Opus Encoder] -> {Send Queue} -> (Server) + * 2. (Server) -> {Decode Queue} -> [Opus Decoder] -> {Playback Queue} -> (Speaker) + * + * We use one task for MIC / Speaker / Processors, and one task for Opus Encoder / Opus Decoder. + * + * Decode Queue and Send Queue are the main queues, because Opus packets are quite smaller than PCM packets. + * + */ + +#define OPUS_FRAME_DURATION_MS 60 +#define MAX_ENCODE_TASKS_IN_QUEUE 2 +#define MAX_PLAYBACK_TASKS_IN_QUEUE 2 +#define MAX_DECODE_PACKETS_IN_QUEUE (2400 / OPUS_FRAME_DURATION_MS) +#define MAX_SEND_PACKETS_IN_QUEUE (2400 / OPUS_FRAME_DURATION_MS) +#define AUDIO_TESTING_MAX_DURATION_MS 10000 +#define MAX_TIMESTAMPS_IN_QUEUE 3 + +#define AUDIO_POWER_TIMEOUT_MS 15000 +#define AUDIO_POWER_CHECK_INTERVAL_MS 1000 + + +#define AS_EVENT_AUDIO_TESTING_RUNNING (1 << 0) +#define AS_EVENT_WAKE_WORD_RUNNING (1 << 1) +#define AS_EVENT_AUDIO_PROCESSOR_RUNNING (1 << 2) +#define AS_EVENT_PLAYBACK_NOT_EMPTY (1 << 3) + +struct AudioServiceCallbacks { + std::function on_send_queue_available; + std::function on_wake_word_detected; + std::function on_vad_change; + std::function on_audio_testing_queue_full; +}; + + +enum AudioTaskType { + kAudioTaskTypeEncodeToSendQueue, + kAudioTaskTypeEncodeToTestingQueue, + kAudioTaskTypeDecodeToPlaybackQueue, +}; + +struct AudioTask { + AudioTaskType type; + std::vector pcm; + uint32_t timestamp; +}; + +struct DebugStatistics { + uint32_t input_count = 0; + uint32_t decode_count = 0; + uint32_t encode_count = 0; + uint32_t playback_count = 0; +}; + +class AudioService { +public: + AudioService(); + ~AudioService(); + + void Initialize(AudioCodec* codec); + void Start(); + void Stop(); + void EncodeWakeWord(); + std::unique_ptr PopWakeWordPacket(); + const std::string& GetLastWakeWord() const; + bool IsVoiceDetected() const { return voice_detected_; } + bool IsIdle(); + bool IsWakeWordRunning() const { return xEventGroupGetBits(event_group_) & AS_EVENT_WAKE_WORD_RUNNING; } + bool IsAudioProcessorRunning() const { return xEventGroupGetBits(event_group_) & AS_EVENT_AUDIO_PROCESSOR_RUNNING; } + bool IsAfeWakeWord(); + + void EnableWakeWordDetection(bool enable); + void EnableVoiceProcessing(bool enable); + void EnableAudioTesting(bool enable); + void EnableDeviceAec(bool enable); + + void SetCallbacks(AudioServiceCallbacks& callbacks); + + bool PushPacketToDecodeQueue(std::unique_ptr packet, bool wait = false); + std::unique_ptr PopPacketFromSendQueue(); + void PlaySound(const std::string_view& sound); + bool ReadAudioData(std::vector& data, int sample_rate, int samples); + void ResetDecoder(); + void SetModelsList(srmodel_list_t* models_list); + +private: + AudioCodec* codec_ = nullptr; + AudioServiceCallbacks callbacks_; + std::unique_ptr audio_processor_; + std::unique_ptr wake_word_; + std::unique_ptr audio_debugger_; + std::unique_ptr opus_encoder_; + std::unique_ptr opus_decoder_; + OpusResampler input_resampler_; + OpusResampler reference_resampler_; + OpusResampler output_resampler_; + DebugStatistics debug_statistics_; + srmodel_list_t* models_list_ = nullptr; + + EventGroupHandle_t event_group_; + + // Audio encode / decode + TaskHandle_t audio_input_task_handle_ = nullptr; + TaskHandle_t audio_output_task_handle_ = nullptr; + TaskHandle_t opus_codec_task_handle_ = nullptr; + std::mutex audio_queue_mutex_; + std::condition_variable audio_queue_cv_; + std::deque> audio_decode_queue_; + std::deque> audio_send_queue_; + std::deque> audio_testing_queue_; + std::deque> audio_encode_queue_; + std::deque> audio_playback_queue_; + // For server AEC + std::deque timestamp_queue_; + + bool wake_word_initialized_ = false; + bool audio_processor_initialized_ = false; + bool voice_detected_ = false; + bool service_stopped_ = true; + bool audio_input_need_warmup_ = false; + + esp_timer_handle_t audio_power_timer_ = nullptr; + std::chrono::steady_clock::time_point last_input_time_; + std::chrono::steady_clock::time_point last_output_time_; + + void AudioInputTask(); + void AudioOutputTask(); + void OpusCodecTask(); + void PushTaskToEncodeQueue(AudioTaskType type, std::vector&& pcm); + void SetDecodeSampleRate(int sample_rate, int frame_duration); + void CheckAndUpdateAudioPowerState(); +}; + +#endif \ No newline at end of file diff --git a/main/audio/codecs/box_audio_codec.cc b/main/audio/codecs/box_audio_codec.cc new file mode 100644 index 0000000..a3db34f --- /dev/null +++ b/main/audio/codecs/box_audio_codec.cc @@ -0,0 +1,245 @@ +#include "box_audio_codec.h" + +#include +#include +#include + +#define TAG "BoxAudioCodec" + +BoxAudioCodec::BoxAudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7210_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 30; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = (i2c_port_t)1, + .addr = es8311_addr, + .bus_handle = i2c_master_handle, + }; + out_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(out_ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8311_codec_cfg_t es8311_cfg = {}; + es8311_cfg.ctrl_if = out_ctrl_if_; + es8311_cfg.gpio_if = gpio_if_; + es8311_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_DAC; + es8311_cfg.pa_pin = pa_pin; + es8311_cfg.use_mclk = true; + es8311_cfg.hw_gain.pa_voltage = 5.0; + es8311_cfg.hw_gain.codec_dac_voltage = 3.3; + out_codec_if_ = es8311_codec_new(&es8311_cfg); + assert(out_codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = out_codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + + // Input + i2c_cfg.addr = es7210_addr; + in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7210_codec_cfg_t es7210_cfg = {}; + es7210_cfg.ctrl_if = in_ctrl_if_; + es7210_cfg.mic_selected = ES7210_SEL_MIC1 | ES7210_SEL_MIC2 | ES7210_SEL_MIC3 | ES7210_SEL_MIC4; + in_codec_if_ = es7210_codec_new(&es7210_cfg); + assert(in_codec_if_ != NULL); + + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + dev_cfg.codec_if = in_codec_if_; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + + ESP_LOGI(TAG, "BoxAudioDevice initialized"); +} + +BoxAudioCodec::~BoxAudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void BoxAudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + i2s_tdm_config_t tdm_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + .bclk_div = 8, + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = i2s_tdm_slot_mask_t(I2S_TDM_SLOT0 | I2S_TDM_SLOT1 | I2S_TDM_SLOT2 | I2S_TDM_SLOT3), + .ws_width = I2S_TDM_AUTO_WS_WIDTH, + .ws_pol = false, + .bit_shift = true, + .left_align = false, + .big_endian = false, + .bit_order_lsb = false, + .skip_mask = false, + .total_slot = I2S_TDM_AUTO_SLOT_NUM + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = I2S_GPIO_UNUSED, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_tdm_mode(rx_handle_, &tdm_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void BoxAudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void BoxAudioCodec::EnableInput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 4, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + if (input_reference_) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_channel_gain(input_dev_, ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), input_gain_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void BoxAudioCodec::EnableOutput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + } + AudioCodec::EnableOutput(enable); +} + +int BoxAudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int BoxAudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} \ No newline at end of file diff --git a/main/audio/codecs/box_audio_codec.h b/main/audio/codecs/box_audio_codec.h new file mode 100644 index 0000000..cb7d389 --- /dev/null +++ b/main/audio/codecs/box_audio_codec.h @@ -0,0 +1,40 @@ +#ifndef _BOX_AUDIO_CODEC_H +#define _BOX_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include + + +class BoxAudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + std::mutex data_if_mutex_; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + BoxAudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7210_addr, bool input_reference); + virtual ~BoxAudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/audio/codecs/dummy_audio_codec.cc b/main/audio/codecs/dummy_audio_codec.cc new file mode 100644 index 0000000..5f646b3 --- /dev/null +++ b/main/audio/codecs/dummy_audio_codec.cc @@ -0,0 +1,20 @@ +#include "dummy_audio_codec.h" + +DummyAudioCodec::DummyAudioCodec(int input_sample_rate, int output_sample_rate) { + duplex_ = true; + input_reference_ = false; + input_channels_ = 1; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; +} + +DummyAudioCodec::~DummyAudioCodec() { +} + +int DummyAudioCodec::Read(int16_t* dest, int samples) { + return 0; +} + +int DummyAudioCodec::Write(const int16_t* data, int samples) { + return 0; +} diff --git a/main/audio/codecs/dummy_audio_codec.h b/main/audio/codecs/dummy_audio_codec.h new file mode 100644 index 0000000..158f140 --- /dev/null +++ b/main/audio/codecs/dummy_audio_codec.h @@ -0,0 +1,16 @@ +#ifndef _DUMMY_AUDIO_CODEC_H +#define _DUMMY_AUDIO_CODEC_H + +#include "audio_codec.h" + +class DummyAudioCodec : public AudioCodec { +private: + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + DummyAudioCodec(int input_sample_rate, int output_sample_rate); + virtual ~DummyAudioCodec(); +}; + +#endif // _DUMMY_AUDIO_CODEC_H \ No newline at end of file diff --git a/main/audio/codecs/es8311_audio_codec.cc b/main/audio/codecs/es8311_audio_codec.cc new file mode 100644 index 0000000..0a03e87 --- /dev/null +++ b/main/audio/codecs/es8311_audio_codec.cc @@ -0,0 +1,197 @@ +#include "es8311_audio_codec.h" + +#include + +#define TAG "Es8311AudioCodec" + +Es8311AudioCodec::Es8311AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, bool use_mclk, bool pa_inverted) { + duplex_ = true; // 是否双工 + input_reference_ = false; // 是否使用参考输入,实现回声消除 + input_channels_ = 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + pa_pin_ = pa_pin; + pa_inverted_ = pa_inverted; + input_gain_ = 30; + + assert(input_sample_rate_ == output_sample_rate_); + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = i2c_port, + .addr = es8311_addr, + .bus_handle = i2c_master_handle, + }; + ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8311_codec_cfg_t es8311_cfg = {}; + es8311_cfg.ctrl_if = ctrl_if_; + es8311_cfg.gpio_if = gpio_if_; + es8311_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_BOTH; + es8311_cfg.pa_pin = pa_pin; + es8311_cfg.use_mclk = use_mclk; + es8311_cfg.hw_gain.pa_voltage = 5.0; + es8311_cfg.hw_gain.codec_dac_voltage = 3.3; + es8311_cfg.pa_reverted = pa_inverted_; + codec_if_ = es8311_codec_new(&es8311_cfg); + + if (codec_if_ == nullptr) { + ESP_LOGE(TAG, "Failed to create Es8311AudioCodec"); + } else { + ESP_LOGI(TAG, "Es8311AudioCodec initialized"); + } +} + +Es8311AudioCodec::~Es8311AudioCodec() { + esp_codec_dev_delete(dev_); + + audio_codec_delete_codec_if(codec_if_); + audio_codec_delete_ctrl_if(ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Es8311AudioCodec::UpdateDeviceState() { + if ((input_enabled_ || output_enabled_) && dev_ == nullptr) { + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_IN_OUT, + .codec_if = codec_if_, + .data_if = data_if_, + }; + dev_ = esp_codec_dev_new(&dev_cfg); + assert(dev_ != NULL); + + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(dev_, input_gain_)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(dev_, output_volume_)); + } else if (!input_enabled_ && !output_enabled_ && dev_ != nullptr) { + esp_codec_dev_close(dev_); + dev_ = nullptr; + } + if (pa_pin_ != GPIO_NUM_NC) { + int level = output_enabled_ ? 1 : 0; + gpio_set_level(pa_pin_, pa_inverted_ ? !level : level); + } +} + +void Es8311AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void Es8311AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void Es8311AudioCodec::EnableInput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (codec_if_ == nullptr) { + return; + } + if (enable == input_enabled_) { + return; + } + AudioCodec::EnableInput(enable); + UpdateDeviceState(); +} + +void Es8311AudioCodec::EnableOutput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (codec_if_ == nullptr) { + return; + } + if (enable == output_enabled_) { + return; + } + AudioCodec::EnableOutput(enable); + UpdateDeviceState(); +} + +int Es8311AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int Es8311AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} \ No newline at end of file diff --git a/main/audio/codecs/es8311_audio_codec.h b/main/audio/codecs/es8311_audio_codec.h new file mode 100644 index 0000000..dd0e639 --- /dev/null +++ b/main/audio/codecs/es8311_audio_codec.h @@ -0,0 +1,42 @@ +#ifndef _ES8311_AUDIO_CODEC_H +#define _ES8311_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include +#include +#include + + +class Es8311AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* ctrl_if_ = nullptr; + const audio_codec_if_t* codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t dev_ = nullptr; + gpio_num_t pa_pin_ = GPIO_NUM_NC; + bool pa_inverted_ = false; + std::mutex data_if_mutex_; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + void UpdateDeviceState(); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + Es8311AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, bool use_mclk = true, bool pa_inverted = false); + virtual ~Es8311AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _ES8311_AUDIO_CODEC_H \ No newline at end of file diff --git a/main/audio/codecs/es8374_audio_codec.cc b/main/audio/codecs/es8374_audio_codec.cc new file mode 100644 index 0000000..30b1ba3 --- /dev/null +++ b/main/audio/codecs/es8374_audio_codec.cc @@ -0,0 +1,198 @@ +#include "es8374_audio_codec.h" + +#include + +#define TAG "Es8374AudioCodec" + +Es8374AudioCodec::Es8374AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8374_addr, bool use_mclk) { + duplex_ = true; // 是否双工 + input_reference_ = false; // 是否使用参考输入,实现回声消除 + input_channels_ = 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 30; + + pa_pin_ = pa_pin; + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = i2c_port, + .addr = es8374_addr, + .bus_handle = i2c_master_handle, + }; + ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8374_codec_cfg_t es8374_cfg = {}; + es8374_cfg.ctrl_if = ctrl_if_; + es8374_cfg.gpio_if = gpio_if_; + es8374_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_BOTH; + es8374_cfg.pa_pin = pa_pin; + codec_if_ = es8374_codec_new(&es8374_cfg); + assert(codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + esp_codec_set_disable_when_closed(output_dev_, false); + esp_codec_set_disable_when_closed(input_dev_, false); + ESP_LOGI(TAG, "Es8374AudioCodec initialized"); +} + +Es8374AudioCodec::~Es8374AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(codec_if_); + audio_codec_delete_ctrl_if(ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Es8374AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = 6, + .dma_frame_num = 240, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void Es8374AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void Es8374AudioCodec::EnableInput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, input_gain_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void Es8374AudioCodec::EnableOutput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 1); + } + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 0); + } + } + AudioCodec::EnableOutput(enable); +} + +int Es8374AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int Es8374AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} \ No newline at end of file diff --git a/main/audio/codecs/es8374_audio_codec.h b/main/audio/codecs/es8374_audio_codec.h new file mode 100644 index 0000000..7533c22 --- /dev/null +++ b/main/audio/codecs/es8374_audio_codec.h @@ -0,0 +1,41 @@ +#ifndef _ES8374_AUDIO_CODEC_H +#define _ES8374_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include +#include +#include + + +class Es8374AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* ctrl_if_ = nullptr; + const audio_codec_if_t* codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + gpio_num_t pa_pin_ = GPIO_NUM_NC; + std::mutex data_if_mutex_; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + Es8374AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8374_addr, bool use_mclk = true); + virtual ~Es8374AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _ES8374_AUDIO_CODEC_H \ No newline at end of file diff --git a/main/audio/codecs/es8388_audio_codec.cc b/main/audio/codecs/es8388_audio_codec.cc new file mode 100644 index 0000000..aa26ae7 --- /dev/null +++ b/main/audio/codecs/es8388_audio_codec.cc @@ -0,0 +1,221 @@ +#include "es8388_audio_codec.h" + +#include + +#define TAG "Es8388AudioCodec" + +Es8388AudioCodec::Es8388AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8388_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 24; + + pa_pin_ = pa_pin; + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = i2c_port, + .addr = es8388_addr, + .bus_handle = i2c_master_handle, + }; + ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8388_codec_cfg_t es8388_cfg = {}; + es8388_cfg.ctrl_if = ctrl_if_; + es8388_cfg.gpio_if = gpio_if_; + es8388_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_BOTH; + es8388_cfg.master_mode = true; + es8388_cfg.pa_pin = pa_pin; + es8388_cfg.pa_reverted = false; + es8388_cfg.hw_gain.pa_voltage = 5.0; + es8388_cfg.hw_gain.codec_dac_voltage = 3.3; + codec_if_ = es8388_codec_new(&es8388_cfg); + assert(codec_if_ != NULL); + + esp_codec_dev_cfg_t outdev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&outdev_cfg); + assert(output_dev_ != NULL); + + esp_codec_dev_cfg_t indev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_IN, + .codec_if = codec_if_, + .data_if = data_if_, + }; + input_dev_ = esp_codec_dev_new(&indev_cfg); + assert(input_dev_ != NULL); + esp_codec_set_disable_when_closed(output_dev_, false); + esp_codec_set_disable_when_closed(input_dev_, false); + ESP_LOGI(TAG, "Es8388AudioCodec initialized"); +} + +Es8388AudioCodec::~Es8388AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(codec_if_); + audio_codec_delete_ctrl_if(ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Es8388AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din){ + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void Es8388AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void Es8388AudioCodec::EnableInput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = (uint8_t) input_channels_, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + if (input_reference_) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + if (input_reference_) { + uint8_t gain = (11 << 4) + 0; + ctrl_if_->write_reg(ctrl_if_, 0x09, 1, &gain, 1); + }else{ + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, input_gain_)); + } + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void Es8388AudioCodec::EnableOutput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == output_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + + // Set analog output volume to 0dB, default is -45dB + uint8_t reg_val = 30; // 0dB + if(input_reference_){ + reg_val = 27; + } + uint8_t regs[] = { 46, 47, 48, 49 }; // HP_LVOL, HP_RVOL, SPK_LVOL, SPK_RVOL + for (uint8_t reg : regs) { + ctrl_if_->write_reg(ctrl_if_, reg, 1, ®_val, 1); + } + + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 1); + } + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 0); + } + } + AudioCodec::EnableOutput(enable); +} + +int Es8388AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int Es8388AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_ && output_dev_ && data != nullptr) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} diff --git a/main/audio/codecs/es8388_audio_codec.h b/main/audio/codecs/es8388_audio_codec.h new file mode 100644 index 0000000..316dfce --- /dev/null +++ b/main/audio/codecs/es8388_audio_codec.h @@ -0,0 +1,40 @@ +#ifndef _ES8388_AUDIO_CODEC_H +#define _ES8388_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include +#include + + +class Es8388AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* ctrl_if_ = nullptr; + const audio_codec_if_t* codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + gpio_num_t pa_pin_ = GPIO_NUM_NC; + std::mutex data_if_mutex_; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + Es8388AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8388_addr, bool input_reference = false); + virtual ~Es8388AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _ES8388_AUDIO_CODEC_H diff --git a/main/audio/codecs/es8389_audio_codec.cc b/main/audio/codecs/es8389_audio_codec.cc new file mode 100644 index 0000000..351ad45 --- /dev/null +++ b/main/audio/codecs/es8389_audio_codec.cc @@ -0,0 +1,204 @@ +#include "es8389_audio_codec.h" + +#include + +static const char TAG[] = "Es8389AudioCodec"; + +Es8389AudioCodec::Es8389AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8389_addr, bool use_mclk) { + duplex_ = true; // 是否双工 + input_reference_ = false; // 是否使用参考输入,实现回声消除 + input_channels_ = 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 40; + pa_pin_ = pa_pin; + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = i2c_port, + .addr = es8389_addr, + .bus_handle = i2c_master_handle, + }; + ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8389_codec_cfg_t es8389_cfg = {}; + es8389_cfg.ctrl_if = ctrl_if_; + es8389_cfg.gpio_if = gpio_if_; + es8389_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_BOTH; + es8389_cfg.pa_pin = pa_pin; + es8389_cfg.use_mclk = use_mclk; + es8389_cfg.hw_gain.pa_voltage = 5.0; + es8389_cfg.hw_gain.codec_dac_voltage = 3.3; + codec_if_ = es8389_codec_new(&es8389_cfg); + + assert(codec_if_ != NULL); + + esp_codec_dev_cfg_t outdev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&outdev_cfg); + assert(output_dev_ != NULL); + + esp_codec_dev_cfg_t indev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_IN, + .codec_if = codec_if_, + .data_if = data_if_, + }; + input_dev_ = esp_codec_dev_new(&indev_cfg); + assert(input_dev_ != NULL); + esp_codec_set_disable_when_closed(output_dev_, false); + esp_codec_set_disable_when_closed(input_dev_, false); + ESP_LOGI(TAG, "Es8389AudioCodec initialized"); +} + +Es8389AudioCodec::~Es8389AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(codec_if_); + audio_codec_delete_ctrl_if(ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Es8389AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = 6, + .dma_frame_num = 240, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, +#ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, +#endif + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void Es8389AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void Es8389AudioCodec::EnableInput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, input_gain_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void Es8389AudioCodec::EnableOutput(bool enable) { + std::lock_guard lock(data_if_mutex_); + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 1); + } + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 0); + } + } + AudioCodec::EnableOutput(enable); +} + +int Es8389AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int Es8389AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} \ No newline at end of file diff --git a/main/audio/codecs/es8389_audio_codec.h b/main/audio/codecs/es8389_audio_codec.h new file mode 100644 index 0000000..b55b427 --- /dev/null +++ b/main/audio/codecs/es8389_audio_codec.h @@ -0,0 +1,40 @@ +#ifndef _ES8389_AUDIO_CODEC_H +#define _ES8389_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include +#include +#include + +class Es8389AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* ctrl_if_ = nullptr; + const audio_codec_if_t* codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + gpio_num_t pa_pin_ = GPIO_NUM_NC; + std::mutex data_if_mutex_; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + Es8389AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8389_addr, bool use_mclk = true); + virtual ~Es8389AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _ES8389_AUDIO_CODEC_H diff --git a/main/audio/codecs/no_audio_codec.cc b/main/audio/codecs/no_audio_codec.cc new file mode 100644 index 0000000..4c839c8 --- /dev/null +++ b/main/audio/codecs/no_audio_codec.cc @@ -0,0 +1,359 @@ +#include "no_audio_codec.h" + +#include +#include +#include + +#define TAG "NoAudioCodec" + +NoAudioCodec::~NoAudioCodec() { + if (rx_handle_ != nullptr) { + ESP_ERROR_CHECK(i2s_channel_disable(rx_handle_)); + } + if (tx_handle_ != nullptr) { + ESP_ERROR_CHECK(i2s_channel_disable(tx_handle_)); + } +} + +NoAudioCodecDuplex::NoAudioCodecDuplex(int input_sample_rate, int output_sample_rate, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + duplex_ = true; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_32BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = I2S_STD_SLOT_LEFT, + .ws_width = I2S_DATA_BIT_WIDTH_32BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + + }, + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + + +NoAudioCodecSimplex::NoAudioCodecSimplex(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, gpio_num_t mic_sck, gpio_num_t mic_ws, gpio_num_t mic_din) { + duplex_ = false; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + // Create a new channel for speaker + i2s_chan_config_t chan_cfg = { + .id = (i2s_port_t)0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, nullptr)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_32BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = I2S_STD_SLOT_LEFT, + .ws_width = I2S_DATA_BIT_WIDTH_32BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + + }, + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = spk_bclk, + .ws = spk_ws, + .dout = spk_dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + + // Create a new channel for MIC + chan_cfg.id = (i2s_port_t)1; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, nullptr, &rx_handle_)); + std_cfg.clk_cfg.sample_rate_hz = (uint32_t)input_sample_rate_; + std_cfg.gpio_cfg.bclk = mic_sck; + std_cfg.gpio_cfg.ws = mic_ws; + std_cfg.gpio_cfg.dout = I2S_GPIO_UNUSED; + std_cfg.gpio_cfg.din = mic_din; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Simplex channels created"); +} + +NoAudioCodecSimplex::NoAudioCodecSimplex(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, i2s_std_slot_mask_t spk_slot_mask, gpio_num_t mic_sck, gpio_num_t mic_ws, gpio_num_t mic_din, i2s_std_slot_mask_t mic_slot_mask){ + duplex_ = false; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + // Create a new channel for speaker + i2s_chan_config_t chan_cfg = { + .id = (i2s_port_t)0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, nullptr)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_32BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = spk_slot_mask, + .ws_width = I2S_DATA_BIT_WIDTH_32BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + + }, + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = spk_bclk, + .ws = spk_ws, + .dout = spk_dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + + // Create a new channel for MIC + chan_cfg.id = (i2s_port_t)1; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, nullptr, &rx_handle_)); + std_cfg.clk_cfg.sample_rate_hz = (uint32_t)input_sample_rate_; + std_cfg.slot_cfg.slot_mask = mic_slot_mask; + std_cfg.gpio_cfg.bclk = mic_sck; + std_cfg.gpio_cfg.ws = mic_ws; + std_cfg.gpio_cfg.dout = I2S_GPIO_UNUSED; + std_cfg.gpio_cfg.din = mic_din; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Simplex channels created"); +} + +int NoAudioCodec::Write(const int16_t* data, int samples) { + std::lock_guard lock(data_if_mutex_); + std::vector buffer(samples); + + // output_volume_: 0-100 + // volume_factor_: 0-65536 + int32_t volume_factor = pow(double(output_volume_) / 100.0, 2) * 65536; + for (int i = 0; i < samples; i++) { + int64_t temp = int64_t(data[i]) * volume_factor; // 使用 int64_t 进行乘法运算 + if (temp > INT32_MAX) { + buffer[i] = INT32_MAX; + } else if (temp < INT32_MIN) { + buffer[i] = INT32_MIN; + } else { + buffer[i] = static_cast(temp); + } + } + + size_t bytes_written; + ESP_ERROR_CHECK(i2s_channel_write(tx_handle_, buffer.data(), samples * sizeof(int32_t), &bytes_written, portMAX_DELAY)); + return bytes_written / sizeof(int32_t); +} + +int NoAudioCodec::Read(int16_t* dest, int samples) { + size_t bytes_read; + + std::vector bit32_buffer(samples); + if (i2s_channel_read(rx_handle_, bit32_buffer.data(), samples * sizeof(int32_t), &bytes_read, portMAX_DELAY) != ESP_OK) { + ESP_LOGE(TAG, "Read Failed!"); + return 0; + } + + samples = bytes_read / sizeof(int32_t); + for (int i = 0; i < samples; i++) { + int32_t value = bit32_buffer[i] >> 12; + dest[i] = (value > INT16_MAX) ? INT16_MAX : (value < -INT16_MAX) ? -INT16_MAX : (int16_t)value; + } + return samples; +} + +// Delegating constructor: calls the main constructor with default slot mask +NoAudioCodecSimplexPdm::NoAudioCodecSimplexPdm(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, gpio_num_t mic_sck, gpio_num_t mic_din) + : NoAudioCodecSimplexPdm(input_sample_rate, output_sample_rate, spk_bclk, spk_ws, spk_dout, I2S_STD_SLOT_LEFT, mic_sck, mic_din) { + // All initialization is handled by the delegated constructor +} + +NoAudioCodecSimplexPdm::NoAudioCodecSimplexPdm(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, i2s_std_slot_mask_t spk_slot_mask, gpio_num_t mic_sck, gpio_num_t mic_din) { + duplex_ = false; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + // Create a new channel for speaker + i2s_chan_config_t tx_chan_cfg = I2S_CHANNEL_DEFAULT_CONFIG((i2s_port_t)1, I2S_ROLE_MASTER); + tx_chan_cfg.dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM; + tx_chan_cfg.dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM; + tx_chan_cfg.auto_clear_after_cb = true; + tx_chan_cfg.auto_clear_before_cb = false; + tx_chan_cfg.intr_priority = 0; + ESP_ERROR_CHECK(i2s_new_channel(&tx_chan_cfg, &tx_handle_, NULL)); + + + i2s_std_config_t tx_std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_32BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = spk_slot_mask, + .ws_width = I2S_DATA_BIT_WIDTH_32BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + + }, + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = spk_bclk, + .ws = spk_ws, + .dout = spk_dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false, + }, + }, + }; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &tx_std_cfg)); +#if SOC_I2S_SUPPORTS_PDM_RX + // Create a new channel for MIC in PDM mode + i2s_chan_config_t rx_chan_cfg = I2S_CHANNEL_DEFAULT_CONFIG((i2s_port_t)0, I2S_ROLE_MASTER); + ESP_ERROR_CHECK(i2s_new_channel(&rx_chan_cfg, NULL, &rx_handle_)); + i2s_pdm_rx_config_t pdm_rx_cfg = { + .clk_cfg = I2S_PDM_RX_CLK_DEFAULT_CONFIG((uint32_t)input_sample_rate_), + /* The data bit-width of PDM mode is fixed to 16 */ + .slot_cfg = I2S_PDM_RX_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO), + .gpio_cfg = { + .clk = mic_sck, + .din = mic_din, + + .invert_flags = { + .clk_inv = false, + }, + }, + }; + ESP_ERROR_CHECK(i2s_channel_init_pdm_rx_mode(rx_handle_, &pdm_rx_cfg)); +#else + ESP_LOGE(TAG, "PDM is not supported"); +#endif + ESP_LOGI(TAG, "Simplex channels created"); +} + +int NoAudioCodecSimplexPdm::Read(int16_t* dest, int samples) { + size_t bytes_read; + + // PDM 解调后的数据位宽为 16 位,直接读取到目标缓冲区 + if (i2s_channel_read(rx_handle_, dest, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY) != ESP_OK) { + ESP_LOGE(TAG, "Read Failed!"); + return 0; + } + + samples = bytes_read / sizeof(int16_t); + if (input_gain_ > 0) { + int gain_factor = (int)input_gain_; + for (int i = 0; i < samples; i++) { + int32_t amplified = dest[i] * gain_factor; + dest[i] = (amplified > INT16_MAX) ? INT16_MAX : (amplified < -INT16_MAX) ? -INT16_MAX : (int16_t)amplified; + } + } + return samples; +} diff --git a/main/audio/codecs/no_audio_codec.h b/main/audio/codecs/no_audio_codec.h new file mode 100644 index 0000000..098ee00 --- /dev/null +++ b/main/audio/codecs/no_audio_codec.h @@ -0,0 +1,39 @@ +#ifndef _NO_AUDIO_CODEC_H +#define _NO_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include + +class NoAudioCodec : public AudioCodec { +protected: + std::mutex data_if_mutex_; + + virtual int Write(const int16_t* data, int samples) override; + virtual int Read(int16_t* dest, int samples) override; + +public: + virtual ~NoAudioCodec(); +}; + +class NoAudioCodecDuplex : public NoAudioCodec { +public: + NoAudioCodecDuplex(int input_sample_rate, int output_sample_rate, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); +}; + +class NoAudioCodecSimplex : public NoAudioCodec { +public: + NoAudioCodecSimplex(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, gpio_num_t mic_sck, gpio_num_t mic_ws, gpio_num_t mic_din); + NoAudioCodecSimplex(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, i2s_std_slot_mask_t spk_slot_mask, gpio_num_t mic_sck, gpio_num_t mic_ws, gpio_num_t mic_din, i2s_std_slot_mask_t mic_slot_mask); +}; + +class NoAudioCodecSimplexPdm : public NoAudioCodec { +public: + NoAudioCodecSimplexPdm(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, gpio_num_t mic_sck, gpio_num_t mic_din); + NoAudioCodecSimplexPdm(int input_sample_rate, int output_sample_rate, gpio_num_t spk_bclk, gpio_num_t spk_ws, gpio_num_t spk_dout, i2s_std_slot_mask_t spk_slot_mask, gpio_num_t mic_sck, gpio_num_t mic_din); + int Read(int16_t* dest, int samples); +}; + +#endif // _NO_AUDIO_CODEC_H diff --git a/main/audio/processors/afe_audio_processor.cc b/main/audio/processors/afe_audio_processor.cc new file mode 100644 index 0000000..0281b13 --- /dev/null +++ b/main/audio/processors/afe_audio_processor.cc @@ -0,0 +1,187 @@ +#include "afe_audio_processor.h" +#include + +#define PROCESSOR_RUNNING 0x01 + +#define TAG "AfeAudioProcessor" + +AfeAudioProcessor::AfeAudioProcessor() + : afe_data_(nullptr) { + event_group_ = xEventGroupCreate(); +} + +void AfeAudioProcessor::Initialize(AudioCodec* codec, int frame_duration_ms, srmodel_list_t* models_list) { + codec_ = codec; + frame_samples_ = frame_duration_ms * 16000 / 1000; + + // Pre-allocate output buffer capacity + output_buffer_.reserve(frame_samples_); + + int ref_num = codec_->input_reference() ? 1 : 0; + + std::string input_format; + for (int i = 0; i < codec_->input_channels() - ref_num; i++) { + input_format.push_back('M'); + } + for (int i = 0; i < ref_num; i++) { + input_format.push_back('R'); + } + + srmodel_list_t *models; + if (models_list == nullptr) { + models = esp_srmodel_init("model"); + } else { + models = models_list; + } + + char* ns_model_name = esp_srmodel_filter(models, ESP_NSNET_PREFIX, NULL); + char* vad_model_name = esp_srmodel_filter(models, ESP_VADN_PREFIX, NULL); + + afe_config_t* afe_config = afe_config_init(input_format.c_str(), NULL, AFE_TYPE_VC, AFE_MODE_HIGH_PERF); + afe_config->aec_mode = AEC_MODE_VOIP_HIGH_PERF; + afe_config->vad_mode = VAD_MODE_0; + afe_config->vad_min_noise_ms = 100; + if (vad_model_name != nullptr) { + afe_config->vad_model_name = vad_model_name; + } + + if (ns_model_name != nullptr) { + afe_config->ns_init = true; + afe_config->ns_model_name = ns_model_name; + afe_config->afe_ns_mode = AFE_NS_MODE_NET; + } else { + afe_config->ns_init = false; + } + + afe_config->agc_init = false; + afe_config->memory_alloc_mode = AFE_MEMORY_ALLOC_MORE_PSRAM; + +#ifdef CONFIG_USE_DEVICE_AEC + afe_config->aec_init = true; + afe_config->vad_init = false; +#else + afe_config->aec_init = false; + afe_config->vad_init = true; +#endif + + afe_iface_ = esp_afe_handle_from_config(afe_config); + afe_data_ = afe_iface_->create_from_config(afe_config); + + xTaskCreate([](void* arg) { + auto this_ = (AfeAudioProcessor*)arg; + this_->AudioProcessorTask(); + vTaskDelete(NULL); + }, "audio_communication", 4096, this, 3, NULL); +} + +AfeAudioProcessor::~AfeAudioProcessor() { + if (afe_data_ != nullptr) { + afe_iface_->destroy(afe_data_); + } + vEventGroupDelete(event_group_); +} + +size_t AfeAudioProcessor::GetFeedSize() { + if (afe_data_ == nullptr) { + return 0; + } + return afe_iface_->get_feed_chunksize(afe_data_); +} + +void AfeAudioProcessor::Feed(std::vector&& data) { + if (afe_data_ == nullptr) { + return; + } + afe_iface_->feed(afe_data_, data.data()); +} + +void AfeAudioProcessor::Start() { + xEventGroupSetBits(event_group_, PROCESSOR_RUNNING); +} + +void AfeAudioProcessor::Stop() { + xEventGroupClearBits(event_group_, PROCESSOR_RUNNING); + if (afe_data_ != nullptr) { + afe_iface_->reset_buffer(afe_data_); + } +} + +bool AfeAudioProcessor::IsRunning() { + return xEventGroupGetBits(event_group_) & PROCESSOR_RUNNING; +} + +void AfeAudioProcessor::OnOutput(std::function&& data)> callback) { + output_callback_ = callback; +} + +void AfeAudioProcessor::OnVadStateChange(std::function callback) { + vad_state_change_callback_ = callback; +} + +void AfeAudioProcessor::AudioProcessorTask() { + auto fetch_size = afe_iface_->get_fetch_chunksize(afe_data_); + auto feed_size = afe_iface_->get_feed_chunksize(afe_data_); + ESP_LOGI(TAG, "Audio communication task started, feed size: %d fetch size: %d", + feed_size, fetch_size); + + while (true) { + xEventGroupWaitBits(event_group_, PROCESSOR_RUNNING, pdFALSE, pdTRUE, portMAX_DELAY); + + auto res = afe_iface_->fetch_with_delay(afe_data_, portMAX_DELAY); + if ((xEventGroupGetBits(event_group_) & PROCESSOR_RUNNING) == 0) { + continue; + } + if (res == nullptr || res->ret_value == ESP_FAIL) { + if (res != nullptr) { + ESP_LOGI(TAG, "Error code: %d", res->ret_value); + } + continue; + } + + // VAD state change + if (vad_state_change_callback_) { + if (res->vad_state == VAD_SPEECH && !is_speaking_) { + is_speaking_ = true; + vad_state_change_callback_(true); + } else if (res->vad_state == VAD_SILENCE && is_speaking_) { + is_speaking_ = false; + vad_state_change_callback_(false); + } + } + + if (output_callback_) { + size_t samples = res->data_size / sizeof(int16_t); + + // Add data to buffer + output_buffer_.insert(output_buffer_.end(), res->data, res->data + samples); + + // Output complete frames when buffer has enough data + while (output_buffer_.size() >= frame_samples_) { + if (output_buffer_.size() == frame_samples_) { + // If buffer size equals frame size, move the entire buffer + output_callback_(std::move(output_buffer_)); + output_buffer_.clear(); + output_buffer_.reserve(frame_samples_); + } else { + // If buffer size exceeds frame size, copy one frame and remove it + output_callback_(std::vector(output_buffer_.begin(), output_buffer_.begin() + frame_samples_)); + output_buffer_.erase(output_buffer_.begin(), output_buffer_.begin() + frame_samples_); + } + } + } + } +} + +void AfeAudioProcessor::EnableDeviceAec(bool enable) { + if (enable) { +#if CONFIG_USE_DEVICE_AEC + afe_iface_->disable_vad(afe_data_); + afe_iface_->enable_aec(afe_data_); +#else + ESP_LOGE(TAG, "Device AEC is not supported"); +#endif + } else { + afe_iface_->disable_aec(afe_data_); + afe_iface_->enable_vad(afe_data_); + } +} diff --git a/main/audio/processors/afe_audio_processor.h b/main/audio/processors/afe_audio_processor.h new file mode 100644 index 0000000..74d7fa4 --- /dev/null +++ b/main/audio/processors/afe_audio_processor.h @@ -0,0 +1,45 @@ +#ifndef AFE_AUDIO_PROCESSOR_H +#define AFE_AUDIO_PROCESSOR_H + +#include +#include +#include +#include + +#include +#include +#include + +#include "audio_processor.h" +#include "audio_codec.h" + +class AfeAudioProcessor : public AudioProcessor { +public: + AfeAudioProcessor(); + ~AfeAudioProcessor(); + + void Initialize(AudioCodec* codec, int frame_duration_ms, srmodel_list_t* models_list) override; + void Feed(std::vector&& data) override; + void Start() override; + void Stop() override; + bool IsRunning() override; + void OnOutput(std::function&& data)> callback) override; + void OnVadStateChange(std::function callback) override; + size_t GetFeedSize() override; + void EnableDeviceAec(bool enable) override; + +private: + EventGroupHandle_t event_group_ = nullptr; + const esp_afe_sr_iface_t* afe_iface_ = nullptr; + esp_afe_sr_data_t* afe_data_ = nullptr; + std::function&& data)> output_callback_; + std::function vad_state_change_callback_; + AudioCodec* codec_ = nullptr; + int frame_samples_ = 0; + bool is_speaking_ = false; + std::vector output_buffer_; + + void AudioProcessorTask(); +}; + +#endif \ No newline at end of file diff --git a/main/audio/processors/audio_debugger.cc b/main/audio/processors/audio_debugger.cc new file mode 100644 index 0000000..630057c --- /dev/null +++ b/main/audio/processors/audio_debugger.cc @@ -0,0 +1,68 @@ +#include "audio_debugger.h" +#include "sdkconfig.h" + +#if CONFIG_USE_AUDIO_DEBUGGER +#include +#include +#include +#include +#include +#include +#endif + +#define TAG "AudioDebugger" + + +AudioDebugger::AudioDebugger() { +#if CONFIG_USE_AUDIO_DEBUGGER + udp_sockfd_ = socket(AF_INET, SOCK_DGRAM, 0); + if (udp_sockfd_ >= 0) { + // 解析配置的服务器地址 "IP:PORT" + std::string server_addr = CONFIG_AUDIO_DEBUG_UDP_SERVER; + size_t colon_pos = server_addr.find(':'); + + if (colon_pos != std::string::npos) { + std::string ip = server_addr.substr(0, colon_pos); + int port = std::stoi(server_addr.substr(colon_pos + 1)); + + memset(&udp_server_addr_, 0, sizeof(udp_server_addr_)); + udp_server_addr_.sin_family = AF_INET; + udp_server_addr_.sin_port = htons(port); + inet_pton(AF_INET, ip.c_str(), &udp_server_addr_.sin_addr); + + ESP_LOGI(TAG, "Initialized server address: %s", CONFIG_AUDIO_DEBUG_UDP_SERVER); + } else { + ESP_LOGW(TAG, "Invalid server address: %s, should be IP:PORT", CONFIG_AUDIO_DEBUG_UDP_SERVER); + close(udp_sockfd_); + udp_sockfd_ = -1; + } + } else { + ESP_LOGW(TAG, "Failed to create UDP socket: %d", errno); + } +#endif +} + +AudioDebugger::~AudioDebugger() { +#if CONFIG_USE_AUDIO_DEBUGGER + if (udp_sockfd_ >= 0) { + close(udp_sockfd_); + ESP_LOGI(TAG, "Closed UDP socket"); + } +#endif +} + +void AudioDebugger::Feed(const std::vector& data) { +#if CONFIG_USE_AUDIO_DEBUGGER + if (udp_sockfd_ >= 0) { + ssize_t sent = sendto(udp_sockfd_, data.data(), data.size() * sizeof(int16_t), 0, + (struct sockaddr*)&udp_server_addr_, sizeof(udp_server_addr_)); + if (sent < 0) { + ESP_LOGW(TAG, "Failed to send audio data to %s: %d", CONFIG_AUDIO_DEBUG_UDP_SERVER, errno); + } else { + ESP_LOGD(TAG, "Sent %d bytes audio data to %s", sent, CONFIG_AUDIO_DEBUG_UDP_SERVER); + } + } +#endif +} + + \ No newline at end of file diff --git a/main/audio/processors/audio_debugger.h b/main/audio/processors/audio_debugger.h new file mode 100644 index 0000000..a81336c --- /dev/null +++ b/main/audio/processors/audio_debugger.h @@ -0,0 +1,22 @@ +#ifndef AUDIO_DEBUGGER_H +#define AUDIO_DEBUGGER_H + +#include +#include + +#include +#include + +class AudioDebugger { +public: + AudioDebugger(); + ~AudioDebugger(); + + void Feed(const std::vector& data); + +private: + int udp_sockfd_ = -1; + struct sockaddr_in udp_server_addr_; +}; + +#endif \ No newline at end of file diff --git a/main/audio/processors/no_audio_processor.cc b/main/audio/processors/no_audio_processor.cc new file mode 100644 index 0000000..bac5bad --- /dev/null +++ b/main/audio/processors/no_audio_processor.cc @@ -0,0 +1,59 @@ +#include "no_audio_processor.h" +#include + +#define TAG "NoAudioProcessor" + +void NoAudioProcessor::Initialize(AudioCodec* codec, int frame_duration_ms, srmodel_list_t* models_list) { + codec_ = codec; + frame_samples_ = frame_duration_ms * 16000 / 1000; +} + +void NoAudioProcessor::Feed(std::vector&& data) { + if (!is_running_ || !output_callback_) { + return; + } + + if (codec_->input_channels() == 2) { + // If input channels is 2, we need to fetch the left channel data + auto mono_data = std::vector(data.size() / 2); + for (size_t i = 0, j = 0; i < mono_data.size(); ++i, j += 2) { + mono_data[i] = data[j]; + } + output_callback_(std::move(mono_data)); + } else { + output_callback_(std::move(data)); + } +} + +void NoAudioProcessor::Start() { + is_running_ = true; +} + +void NoAudioProcessor::Stop() { + is_running_ = false; +} + +bool NoAudioProcessor::IsRunning() { + return is_running_; +} + +void NoAudioProcessor::OnOutput(std::function&& data)> callback) { + output_callback_ = callback; +} + +void NoAudioProcessor::OnVadStateChange(std::function callback) { + vad_state_change_callback_ = callback; +} + +size_t NoAudioProcessor::GetFeedSize() { + if (!codec_) { + return 0; + } + return frame_samples_; +} + +void NoAudioProcessor::EnableDeviceAec(bool enable) { + if (enable) { + ESP_LOGE(TAG, "Device AEC is not supported"); + } +} diff --git a/main/audio/processors/no_audio_processor.h b/main/audio/processors/no_audio_processor.h new file mode 100644 index 0000000..d326d50 --- /dev/null +++ b/main/audio/processors/no_audio_processor.h @@ -0,0 +1,33 @@ +#ifndef DUMMY_AUDIO_PROCESSOR_H +#define DUMMY_AUDIO_PROCESSOR_H + +#include +#include + +#include "audio_processor.h" +#include "audio_codec.h" + +class NoAudioProcessor : public AudioProcessor { +public: + NoAudioProcessor() = default; + ~NoAudioProcessor() = default; + + void Initialize(AudioCodec* codec, int frame_duration_ms, srmodel_list_t* models_list) override; + void Feed(std::vector&& data) override; + void Start() override; + void Stop() override; + bool IsRunning() override; + void OnOutput(std::function&& data)> callback) override; + void OnVadStateChange(std::function callback) override; + size_t GetFeedSize() override; + void EnableDeviceAec(bool enable) override; + +private: + AudioCodec* codec_ = nullptr; + int frame_samples_ = 0; + std::function&& data)> output_callback_; + std::function vad_state_change_callback_; + bool is_running_ = false; +}; + +#endif \ No newline at end of file diff --git a/main/audio/wake_word.h b/main/audio/wake_word.h new file mode 100644 index 0000000..9b8986a --- /dev/null +++ b/main/audio/wake_word.h @@ -0,0 +1,26 @@ +#ifndef WAKE_WORD_H +#define WAKE_WORD_H + +#include +#include +#include + +#include +#include "audio_codec.h" + +class WakeWord { +public: + virtual ~WakeWord() = default; + + virtual bool Initialize(AudioCodec* codec, srmodel_list_t* models_list) = 0; + virtual void Feed(const std::vector& data) = 0; + virtual void OnWakeWordDetected(std::function callback) = 0; + virtual void Start() = 0; + virtual void Stop() = 0; + virtual size_t GetFeedSize() = 0; + virtual void EncodeWakeWordData() = 0; + virtual bool GetWakeWordOpus(std::vector& opus) = 0; + virtual const std::string& GetLastDetectedWakeWord() const = 0; +}; + +#endif diff --git a/main/audio/wake_words/afe_wake_word.cc b/main/audio/wake_words/afe_wake_word.cc new file mode 100644 index 0000000..bcdc697 --- /dev/null +++ b/main/audio/wake_words/afe_wake_word.cc @@ -0,0 +1,208 @@ +#include "afe_wake_word.h" +#include "audio_service.h" + +#include +#include + +#define DETECTION_RUNNING_EVENT 1 + +#define TAG "AfeWakeWord" + +AfeWakeWord::AfeWakeWord() + : afe_data_(nullptr), + wake_word_pcm_(), + wake_word_opus_() { + + event_group_ = xEventGroupCreate(); +} + +AfeWakeWord::~AfeWakeWord() { + if (afe_data_ != nullptr) { + afe_iface_->destroy(afe_data_); + } + + if (wake_word_encode_task_stack_ != nullptr) { + heap_caps_free(wake_word_encode_task_stack_); + } + + if (wake_word_encode_task_buffer_ != nullptr) { + heap_caps_free(wake_word_encode_task_buffer_); + } + + if (models_ != nullptr) { + esp_srmodel_deinit(models_); + } + + vEventGroupDelete(event_group_); +} + +bool AfeWakeWord::Initialize(AudioCodec* codec, srmodel_list_t* models_list) { + codec_ = codec; + int ref_num = codec_->input_reference() ? 1 : 0; + + if (models_list == nullptr) { + models_ = esp_srmodel_init("model"); + } else { + models_ = models_list; + } + + if (models_ == nullptr || models_->num == -1) { + ESP_LOGE(TAG, "Failed to initialize wakenet model"); + return false; + } + for (int i = 0; i < models_->num; i++) { + ESP_LOGI(TAG, "Model %d: %s", i, models_->model_name[i]); + if (strstr(models_->model_name[i], ESP_WN_PREFIX) != NULL) { + wakenet_model_ = models_->model_name[i]; + auto words = esp_srmodel_get_wake_words(models_, wakenet_model_); + // split by ";" to get all wake words + std::stringstream ss(words); + std::string word; + while (std::getline(ss, word, ';')) { + wake_words_.push_back(word); + } + } + } + + std::string input_format; + for (int i = 0; i < codec_->input_channels() - ref_num; i++) { + input_format.push_back('M'); + } + for (int i = 0; i < ref_num; i++) { + input_format.push_back('R'); + } + afe_config_t* afe_config = afe_config_init(input_format.c_str(), models_, AFE_TYPE_SR, AFE_MODE_HIGH_PERF); + afe_config->aec_init = codec_->input_reference(); + afe_config->aec_mode = AEC_MODE_SR_HIGH_PERF; + afe_config->afe_perferred_core = 1; + afe_config->afe_perferred_priority = 1; + afe_config->memory_alloc_mode = AFE_MEMORY_ALLOC_MORE_PSRAM; + + afe_iface_ = esp_afe_handle_from_config(afe_config); + afe_data_ = afe_iface_->create_from_config(afe_config); + + xTaskCreate([](void* arg) { + auto this_ = (AfeWakeWord*)arg; + this_->AudioDetectionTask(); + vTaskDelete(NULL); + }, "audio_detection", 4096, this, 3, nullptr); + + return true; +} + +void AfeWakeWord::OnWakeWordDetected(std::function callback) { + wake_word_detected_callback_ = callback; +} + +void AfeWakeWord::Start() { + xEventGroupSetBits(event_group_, DETECTION_RUNNING_EVENT); +} + +void AfeWakeWord::Stop() { + xEventGroupClearBits(event_group_, DETECTION_RUNNING_EVENT); + if (afe_data_ != nullptr) { + afe_iface_->reset_buffer(afe_data_); + } +} + +void AfeWakeWord::Feed(const std::vector& data) { + if (afe_data_ == nullptr) { + return; + } + afe_iface_->feed(afe_data_, data.data()); +} + +size_t AfeWakeWord::GetFeedSize() { + if (afe_data_ == nullptr) { + return 0; + } + return afe_iface_->get_feed_chunksize(afe_data_); +} + +void AfeWakeWord::AudioDetectionTask() { + auto fetch_size = afe_iface_->get_fetch_chunksize(afe_data_); + auto feed_size = afe_iface_->get_feed_chunksize(afe_data_); + ESP_LOGI(TAG, "Audio detection task started, feed size: %d fetch size: %d", + feed_size, fetch_size); + + while (true) { + xEventGroupWaitBits(event_group_, DETECTION_RUNNING_EVENT, pdFALSE, pdTRUE, portMAX_DELAY); + + auto res = afe_iface_->fetch_with_delay(afe_data_, portMAX_DELAY); + if (res == nullptr || res->ret_value == ESP_FAIL) { + continue;; + } + + // Store the wake word data for voice recognition, like who is speaking + StoreWakeWordData(res->data, res->data_size / sizeof(int16_t)); + + if (res->wakeup_state == WAKENET_DETECTED) { + Stop(); + last_detected_wake_word_ = wake_words_[res->wakenet_model_index - 1]; + + if (wake_word_detected_callback_) { + wake_word_detected_callback_(last_detected_wake_word_); + } + } + } +} + +void AfeWakeWord::StoreWakeWordData(const int16_t* data, size_t samples) { + // store audio data to wake_word_pcm_ + wake_word_pcm_.emplace_back(std::vector(data, data + samples)); + // keep about 2 seconds of data, detect duration is 30ms (sample_rate == 16000, chunksize == 512) + while (wake_word_pcm_.size() > 2000 / 30) { + wake_word_pcm_.pop_front(); + } +} + +void AfeWakeWord::EncodeWakeWordData() { + const size_t stack_size = 4096 * 7; + wake_word_opus_.clear(); + if (wake_word_encode_task_stack_ == nullptr) { + wake_word_encode_task_stack_ = (StackType_t*)heap_caps_malloc(stack_size, MALLOC_CAP_SPIRAM); + assert(wake_word_encode_task_stack_ != nullptr); + } + if (wake_word_encode_task_buffer_ == nullptr) { + wake_word_encode_task_buffer_ = (StaticTask_t*)heap_caps_malloc(sizeof(StaticTask_t), MALLOC_CAP_INTERNAL); + assert(wake_word_encode_task_buffer_ != nullptr); + } + + wake_word_encode_task_ = xTaskCreateStatic([](void* arg) { + auto this_ = (AfeWakeWord*)arg; + { + auto start_time = esp_timer_get_time(); + auto encoder = std::make_unique(16000, 1, OPUS_FRAME_DURATION_MS); + encoder->SetComplexity(0); // 0 is the fastest + + int packets = 0; + for (auto& pcm: this_->wake_word_pcm_) { + encoder->Encode(std::move(pcm), [this_](std::vector&& opus) { + std::lock_guard lock(this_->wake_word_mutex_); + this_->wake_word_opus_.emplace_back(std::move(opus)); + this_->wake_word_cv_.notify_all(); + }); + packets++; + } + this_->wake_word_pcm_.clear(); + + auto end_time = esp_timer_get_time(); + ESP_LOGI(TAG, "Encode wake word opus %d packets in %ld ms", packets, (long)((end_time - start_time) / 1000)); + + std::lock_guard lock(this_->wake_word_mutex_); + this_->wake_word_opus_.push_back(std::vector()); + this_->wake_word_cv_.notify_all(); + } + vTaskDelete(NULL); + }, "encode_wake_word", stack_size, this, 2, wake_word_encode_task_stack_, wake_word_encode_task_buffer_); +} + +bool AfeWakeWord::GetWakeWordOpus(std::vector& opus) { + std::unique_lock lock(wake_word_mutex_); + wake_word_cv_.wait(lock, [this]() { + return !wake_word_opus_.empty(); + }); + opus.swap(wake_word_opus_.front()); + wake_word_opus_.pop_front(); + return !opus.empty(); +} diff --git a/main/audio/wake_words/afe_wake_word.h b/main/audio/wake_words/afe_wake_word.h new file mode 100644 index 0000000..8f5a280 --- /dev/null +++ b/main/audio/wake_words/afe_wake_word.h @@ -0,0 +1,60 @@ +#ifndef AFE_WAKE_WORD_H +#define AFE_WAKE_WORD_H + +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "audio_codec.h" +#include "wake_word.h" + +class AfeWakeWord : public WakeWord { +public: + AfeWakeWord(); + ~AfeWakeWord(); + + bool Initialize(AudioCodec* codec, srmodel_list_t* models_list); + void Feed(const std::vector& data); + void OnWakeWordDetected(std::function callback); + void Start(); + void Stop(); + size_t GetFeedSize(); + void EncodeWakeWordData(); + bool GetWakeWordOpus(std::vector& opus); + const std::string& GetLastDetectedWakeWord() const { return last_detected_wake_word_; } + +private: + srmodel_list_t *models_ = nullptr; + const esp_afe_sr_iface_t* afe_iface_ = nullptr; + esp_afe_sr_data_t* afe_data_ = nullptr; + char* wakenet_model_ = NULL; + std::vector wake_words_; + EventGroupHandle_t event_group_; + std::function wake_word_detected_callback_; + AudioCodec* codec_ = nullptr; + std::string last_detected_wake_word_; + + TaskHandle_t wake_word_encode_task_ = nullptr; + StaticTask_t* wake_word_encode_task_buffer_ = nullptr; + StackType_t* wake_word_encode_task_stack_ = nullptr; + std::deque> wake_word_pcm_; + std::deque> wake_word_opus_; + std::mutex wake_word_mutex_; + std::condition_variable wake_word_cv_; + + void StoreWakeWordData(const int16_t* data, size_t size); + void AudioDetectionTask(); +}; + +#endif diff --git a/main/audio/wake_words/custom_wake_word.cc b/main/audio/wake_words/custom_wake_word.cc new file mode 100644 index 0000000..2a1fb7a --- /dev/null +++ b/main/audio/wake_words/custom_wake_word.cc @@ -0,0 +1,254 @@ +#include "custom_wake_word.h" +#include "audio_service.h" +#include "system_info.h" +#include "assets.h" + +#include +#include +#include +#include +#include + + +#define TAG "CustomWakeWord" + + +CustomWakeWord::CustomWakeWord() + : wake_word_pcm_(), wake_word_opus_() { +} + +CustomWakeWord::~CustomWakeWord() { + if (multinet_model_data_ != nullptr && multinet_ != nullptr) { + multinet_->destroy(multinet_model_data_); + multinet_model_data_ = nullptr; + } + + if (wake_word_encode_task_stack_ != nullptr) { + heap_caps_free(wake_word_encode_task_stack_); + } + + if (wake_word_encode_task_buffer_ != nullptr) { + heap_caps_free(wake_word_encode_task_buffer_); + } + + if (models_ != nullptr) { + esp_srmodel_deinit(models_); + } +} + +void CustomWakeWord::ParseWakenetModelConfig() { + // Read index.json + auto& assets = Assets::GetInstance(); + void* ptr = nullptr; + size_t size = 0; + if (!assets.GetAssetData("index.json", ptr, size)) { + ESP_LOGE(TAG, "Failed to read index.json"); + return; + } + cJSON* root = cJSON_ParseWithLength(static_cast(ptr), size); + if (root == nullptr) { + ESP_LOGE(TAG, "Failed to parse index.json"); + return; + } + cJSON* multinet_model = cJSON_GetObjectItem(root, "multinet_model"); + if (cJSON_IsObject(multinet_model)) { + cJSON* language = cJSON_GetObjectItem(multinet_model, "language"); + cJSON* duration = cJSON_GetObjectItem(multinet_model, "duration"); + cJSON* threshold = cJSON_GetObjectItem(multinet_model, "threshold"); + cJSON* commands = cJSON_GetObjectItem(multinet_model, "commands"); + if (cJSON_IsString(language)) { + language_ = language->valuestring; + } + if (cJSON_IsNumber(duration)) { + duration_ = duration->valueint; + } + if (cJSON_IsNumber(threshold)) { + threshold_ = threshold->valuedouble; + } + if (cJSON_IsArray(commands)) { + for (int i = 0; i < cJSON_GetArraySize(commands); i++) { + cJSON* command = cJSON_GetArrayItem(commands, i); + if (cJSON_IsObject(command)) { + cJSON* command_name = cJSON_GetObjectItem(command, "command"); + cJSON* text = cJSON_GetObjectItem(command, "text"); + cJSON* action = cJSON_GetObjectItem(command, "action"); + if (cJSON_IsString(command_name) && cJSON_IsString(text) && cJSON_IsString(action)) { + commands_.push_back({command_name->valuestring, text->valuestring, action->valuestring}); + ESP_LOGI(TAG, "Command: %s, Text: %s, Action: %s", command_name->valuestring, text->valuestring, action->valuestring); + } + } + } + } + } + cJSON_Delete(root); +} + + +bool CustomWakeWord::Initialize(AudioCodec* codec, srmodel_list_t* models_list) { + codec_ = codec; + commands_.clear(); + + if (models_list == nullptr) { + language_ = "cn"; + models_ = esp_srmodel_init("model"); +#ifdef CONFIG_CUSTOM_WAKE_WORD + threshold_ = CONFIG_CUSTOM_WAKE_WORD_THRESHOLD / 100.0f; + commands_.push_back({CONFIG_CUSTOM_WAKE_WORD, CONFIG_CUSTOM_WAKE_WORD_DISPLAY, "wake"}); +#endif + } else { + models_ = models_list; + ParseWakenetModelConfig(); + } + + if (models_ == nullptr || models_->num == -1) { + ESP_LOGE(TAG, "Failed to initialize wakenet model"); + return false; + } + + // 初始化 multinet (命令词识别) + mn_name_ = esp_srmodel_filter(models_, ESP_MN_PREFIX, language_.c_str()); + if (mn_name_ == nullptr) { + ESP_LOGW(TAG, "Language '%s' multinet not found, falling back to any multinet model", language_.c_str()); + mn_name_ = esp_srmodel_filter(models_, ESP_MN_PREFIX, NULL); + } + if (mn_name_ == nullptr) { + ESP_LOGE(TAG, "Failed to initialize multinet, mn_name is nullptr"); + ESP_LOGI(TAG, "Please refer to https://pcn7cs20v8cr.feishu.cn/wiki/CpQjwQsCJiQSWSkYEvrcxcbVnwh to add custom wake word"); + return false; + } + + multinet_ = esp_mn_handle_from_name(mn_name_); + multinet_model_data_ = multinet_->create(mn_name_, duration_); + multinet_->set_det_threshold(multinet_model_data_, threshold_); + esp_mn_commands_clear(); + for (int i = 0; i < commands_.size(); i++) { + esp_mn_commands_add(i + 1, commands_[i].command.c_str()); + } + esp_mn_commands_update(); + + multinet_->print_active_speech_commands(multinet_model_data_); + return true; +} + +void CustomWakeWord::OnWakeWordDetected(std::function callback) { + wake_word_detected_callback_ = callback; +} + +void CustomWakeWord::Start() { + running_ = true; +} + +void CustomWakeWord::Stop() { + running_ = false; +} + +void CustomWakeWord::Feed(const std::vector& data) { + if (multinet_model_data_ == nullptr || !running_) { + return; + } + + esp_mn_state_t mn_state; + // If input channels is 2, we need to fetch the left channel data + if (codec_->input_channels() == 2) { + auto mono_data = std::vector(data.size() / 2); + for (size_t i = 0, j = 0; i < mono_data.size(); ++i, j += 2) { + mono_data[i] = data[j]; + } + + StoreWakeWordData(mono_data); + mn_state = multinet_->detect(multinet_model_data_, const_cast(mono_data.data())); + } else { + StoreWakeWordData(data); + mn_state = multinet_->detect(multinet_model_data_, const_cast(data.data())); + } + + if (mn_state == ESP_MN_STATE_DETECTING) { + return; + } else if (mn_state == ESP_MN_STATE_DETECTED) { + esp_mn_results_t *mn_result = multinet_->get_results(multinet_model_data_); + for (int i = 0; i < mn_result->num && running_; i++) { + ESP_LOGI(TAG, "Custom wake word detected: command_id=%d, string=%s, prob=%f", + mn_result->command_id[i], mn_result->string, mn_result->prob[i]); + auto& command = commands_[mn_result->command_id[i] - 1]; + if (command.action == "wake") { + last_detected_wake_word_ = command.text; + running_ = false; + + if (wake_word_detected_callback_) { + wake_word_detected_callback_(last_detected_wake_word_); + } + } + } + multinet_->clean(multinet_model_data_); + } else if (mn_state == ESP_MN_STATE_TIMEOUT) { + ESP_LOGD(TAG, "Command word detection timeout, cleaning state"); + multinet_->clean(multinet_model_data_); + } +} + +size_t CustomWakeWord::GetFeedSize() { + if (multinet_model_data_ == nullptr) { + return 0; + } + return multinet_->get_samp_chunksize(multinet_model_data_); +} + +void CustomWakeWord::StoreWakeWordData(const std::vector& data) { + // store audio data to wake_word_pcm_ + wake_word_pcm_.push_back(data); + // keep about 2 seconds of data, detect duration is 30ms (sample_rate == 16000, chunksize == 512) + while (wake_word_pcm_.size() > 2000 / 30) { + wake_word_pcm_.pop_front(); + } +} + +void CustomWakeWord::EncodeWakeWordData() { + const size_t stack_size = 4096 * 7; + wake_word_opus_.clear(); + if (wake_word_encode_task_stack_ == nullptr) { + wake_word_encode_task_stack_ = (StackType_t*)heap_caps_malloc(stack_size, MALLOC_CAP_SPIRAM); + assert(wake_word_encode_task_stack_ != nullptr); + } + if (wake_word_encode_task_buffer_ == nullptr) { + wake_word_encode_task_buffer_ = (StaticTask_t*)heap_caps_malloc(sizeof(StaticTask_t), MALLOC_CAP_INTERNAL); + assert(wake_word_encode_task_buffer_ != nullptr); + } + + wake_word_encode_task_ = xTaskCreateStatic([](void* arg) { + auto this_ = (CustomWakeWord*)arg; + { + auto start_time = esp_timer_get_time(); + auto encoder = std::make_unique(16000, 1, OPUS_FRAME_DURATION_MS); + encoder->SetComplexity(0); // 0 is the fastest + + int packets = 0; + for (auto& pcm: this_->wake_word_pcm_) { + encoder->Encode(std::move(pcm), [this_](std::vector&& opus) { + std::lock_guard lock(this_->wake_word_mutex_); + this_->wake_word_opus_.emplace_back(std::move(opus)); + this_->wake_word_cv_.notify_all(); + }); + packets++; + } + this_->wake_word_pcm_.clear(); + + auto end_time = esp_timer_get_time(); + ESP_LOGI(TAG, "Encode wake word opus %d packets in %ld ms", packets, (long)((end_time - start_time) / 1000)); + + std::lock_guard lock(this_->wake_word_mutex_); + this_->wake_word_opus_.push_back(std::vector()); + this_->wake_word_cv_.notify_all(); + } + vTaskDelete(NULL); + }, "encode_wake_word", stack_size, this, 2, wake_word_encode_task_stack_, wake_word_encode_task_buffer_); +} + +bool CustomWakeWord::GetWakeWordOpus(std::vector& opus) { + std::unique_lock lock(wake_word_mutex_); + wake_word_cv_.wait(lock, [this]() { + return !wake_word_opus_.empty(); + }); + opus.swap(wake_word_opus_.front()); + wake_word_opus_.pop_front(); + return !opus.empty(); +} diff --git a/main/audio/wake_words/custom_wake_word.h b/main/audio/wake_words/custom_wake_word.h new file mode 100644 index 0000000..d4e6d8c --- /dev/null +++ b/main/audio/wake_words/custom_wake_word.h @@ -0,0 +1,69 @@ +#ifndef CUSTOM_WAKE_WORD_H +#define CUSTOM_WAKE_WORD_H + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "audio_codec.h" +#include "wake_word.h" + +class CustomWakeWord : public WakeWord { +public: + CustomWakeWord(); + ~CustomWakeWord(); + + bool Initialize(AudioCodec* codec, srmodel_list_t* models_list); + void Feed(const std::vector& data); + void OnWakeWordDetected(std::function callback); + void Start(); + void Stop(); + size_t GetFeedSize(); + void EncodeWakeWordData(); + bool GetWakeWordOpus(std::vector& opus); + const std::string& GetLastDetectedWakeWord() const { return last_detected_wake_word_; } + +private: + struct Command { + std::string command; + std::string text; + std::string action; + }; + + // multinet 相关成员变量 + esp_mn_iface_t* multinet_ = nullptr; + model_iface_data_t* multinet_model_data_ = nullptr; + srmodel_list_t *models_ = nullptr; + char* mn_name_ = nullptr; + std::string language_ = "cn"; + int duration_ = 3000; + float threshold_ = 0.2; + std::deque commands_; + + std::function wake_word_detected_callback_; + AudioCodec* codec_ = nullptr; + std::string last_detected_wake_word_; + std::atomic running_ = false; + + TaskHandle_t wake_word_encode_task_ = nullptr; + StaticTask_t* wake_word_encode_task_buffer_ = nullptr; + StackType_t* wake_word_encode_task_stack_ = nullptr; + std::deque> wake_word_pcm_; + std::deque> wake_word_opus_; + std::mutex wake_word_mutex_; + std::condition_variable wake_word_cv_; + + void StoreWakeWordData(const std::vector& data); + void ParseWakenetModelConfig(); +}; + +#endif diff --git a/main/audio/wake_words/esp_wake_word.cc b/main/audio/wake_words/esp_wake_word.cc new file mode 100644 index 0000000..d4aaf9d --- /dev/null +++ b/main/audio/wake_words/esp_wake_word.cc @@ -0,0 +1,87 @@ +#include "esp_wake_word.h" +#include + + +#define TAG "EspWakeWord" + +EspWakeWord::EspWakeWord() { +} + +EspWakeWord::~EspWakeWord() { + if (wakenet_data_ != nullptr) { + wakenet_iface_->destroy(wakenet_data_); + esp_srmodel_deinit(wakenet_model_); + } +} + +bool EspWakeWord::Initialize(AudioCodec* codec, srmodel_list_t* models_list) { + codec_ = codec; + + if (models_list == nullptr) { + wakenet_model_ = esp_srmodel_init("model"); + } else { + wakenet_model_ = models_list; + } + + if (wakenet_model_ == nullptr || wakenet_model_->num == -1) { + ESP_LOGE(TAG, "Failed to initialize wakenet model"); + return false; + } + if(wakenet_model_->num > 1) { + ESP_LOGW(TAG, "More than one model found, using the first one"); + } else if (wakenet_model_->num == 0) { + ESP_LOGE(TAG, "No model found"); + return false; + } + char *model_name = wakenet_model_->model_name[0]; + wakenet_iface_ = (esp_wn_iface_t*)esp_wn_handle_from_name(model_name); + wakenet_data_ = wakenet_iface_->create(model_name, DET_MODE_95); + + int frequency = wakenet_iface_->get_samp_rate(wakenet_data_); + int audio_chunksize = wakenet_iface_->get_samp_chunksize(wakenet_data_); + ESP_LOGI(TAG, "Wake word(%s),freq: %d, chunksize: %d", model_name, frequency, audio_chunksize); + + return true; +} + +void EspWakeWord::OnWakeWordDetected(std::function callback) { + wake_word_detected_callback_ = callback; +} + +void EspWakeWord::Start() { + running_ = true; +} + +void EspWakeWord::Stop() { + running_ = false; +} + +void EspWakeWord::Feed(const std::vector& data) { + if (wakenet_data_ == nullptr || !running_) { + return; + } + + int res = wakenet_iface_->detect(wakenet_data_, (int16_t *)data.data()); + if (res > 0) { + last_detected_wake_word_ = wakenet_iface_->get_word_name(wakenet_data_, res); + running_ = false; + + if (wake_word_detected_callback_) { + wake_word_detected_callback_(last_detected_wake_word_); + } + } +} + +size_t EspWakeWord::GetFeedSize() { + if (wakenet_data_ == nullptr) { + return 0; + } + return wakenet_iface_->get_samp_chunksize(wakenet_data_); +} + +void EspWakeWord::EncodeWakeWordData() { +} + +bool EspWakeWord::GetWakeWordOpus(std::vector& opus) { + return false; +} diff --git a/main/audio/wake_words/esp_wake_word.h b/main/audio/wake_words/esp_wake_word.h new file mode 100644 index 0000000..9a1d73a --- /dev/null +++ b/main/audio/wake_words/esp_wake_word.h @@ -0,0 +1,42 @@ +#ifndef ESP_WAKE_WORD_H +#define ESP_WAKE_WORD_H + +#include +#include +#include + +#include +#include +#include +#include + +#include "audio_codec.h" +#include "wake_word.h" + +class EspWakeWord : public WakeWord { +public: + EspWakeWord(); + ~EspWakeWord(); + + bool Initialize(AudioCodec* codec, srmodel_list_t* models_list); + void Feed(const std::vector& data); + void OnWakeWordDetected(std::function callback); + void Start(); + void Stop(); + size_t GetFeedSize(); + void EncodeWakeWordData(); + bool GetWakeWordOpus(std::vector& opus); + const std::string& GetLastDetectedWakeWord() const { return last_detected_wake_word_; } + +private: + esp_wn_iface_t *wakenet_iface_ = nullptr; + model_iface_data_t *wakenet_data_ = nullptr; + srmodel_list_t *wakenet_model_ = nullptr; + AudioCodec* codec_ = nullptr; + std::atomic running_ = false; + + std::function wake_word_detected_callback_; + std::string last_detected_wake_word_; +}; + +#endif diff --git a/main/boards/aipi-lite/README.md b/main/boards/aipi-lite/README.md new file mode 100644 index 0000000..28f5666 --- /dev/null +++ b/main/boards/aipi-lite/README.md @@ -0,0 +1,41 @@ +# 编译命令 + +## 一键编译 + +```bash +python scripts/release.py aipi-lite +``` + +## 手动配置编译 + +```bash +idf.py set-target esp32s3 +``` + +**配置** + +```bash +idf.py menuconfig +``` + +选择板子 + +``` +Xiaozhi Assistant -> Board Type -> AIPI-Lite +``` + +## 编译烧入 + +```bash +idf.py -DBOARD_NAME=aipi-lite build flash +``` + +注意: 如果当前设备出货之前是AiPi-Lite 固件(非小智版本),请特别小心处理闪存固件分区地址,以避免错误擦除 AiPi-Lite 的自身设备信息(EUI 等),否则设备即使恢复成Xorigin固件也无法正确连接到 服务器!所以在刷写固件之前,请务必记录设备的相关必要信息,以确保有恢复的方法! + +您可以使用以下命令备份生产信息 + +```bash +# firstly backup the factory information partition which contains the credentials for connecting the SenseCraft server +esptool.py --chip esp32s3 --baud 2000000 --before default_reset --after hard_reset --no-stub read_flash 0x9000 16384 nvsfactory.bin + +``` \ No newline at end of file diff --git a/main/boards/aipi-lite/README_en.md b/main/boards/aipi-lite/README_en.md new file mode 100644 index 0000000..df9deb5 --- /dev/null +++ b/main/boards/aipi-lite/README_en.md @@ -0,0 +1,40 @@ +# Build Instructions + +## One-click Build + +```bash +python scripts/release.py aipi-lite -c config_en.json +``` + +## Manual Configuration and Build + +```bash +idf.py set-target esp32s3 +``` + +**Configuration** + +```bash +idf.py menuconfig +``` + +Select the board: + +``` +Xiaozhi Assistant -> Board Type -> AiPi-Lite +``` + +## Build and Flash + +```bash +idf.py -DBOARD_NAME=aipi-lite build flash +``` + +Note: If your device was previously shipped with the AiPi-Lite firmware (not the Xiaozhi version), please be very careful with the flash partition addresses to avoid accidentally erasing the device information (such as EUI) of the AiPi-Lite. Otherwise, even if you restore the AiPi-Lite firmware, the device may not be able to connect to the Xorigin server correctly! Therefore, before flashing the firmware, be sure to record the necessary device information to ensure you have a way to recover it! + +You can use the following command to back up the factory information: + +```bash +# Firstly backup the factory information partition which contains the credentials for connecting the SenseCraft server +esptool.py --chip esp32s3 --baud 2000000 --before default_reset --after hard_reset --no-stub read_flash 0x9000 16384 nvsfactory.bin +``` diff --git a/main/boards/aipi-lite/aipi-lite.cc b/main/boards/aipi-lite/aipi-lite.cc new file mode 100644 index 0000000..b808812 --- /dev/null +++ b/main/boards/aipi-lite/aipi-lite.cc @@ -0,0 +1,247 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "application.h" +#include "button.h" +#include "codecs/es8311_audio_codec.h" +#include "config.h" +#include "display/lcd_display.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "power_manager.h" +#include "power_save_timer.h" +#include "system_reset.h" +#include "wifi_board.h" + +#define TAG "AIPI-Lite" + +class AIPILite : public WifiBoard { + private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button power_button_; + LcdDisplay* display_; + PowerManager* power_manager_; + PowerSaveTimer* power_save_timer_; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(POWER_CHARGE_DETECT_PIN); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + esp_lcd_panel_disp_on_off(panel_, false); // 关闭显示 + rtc_gpio_set_level(POWER_CONTROL_PIN, 0); + rtc_gpio_hold_dis(POWER_CONTROL_PIN); + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = + { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SPI_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = + DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK( + spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_SPI_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK( + esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK( + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel_)); + + esp_lcd_panel_reset(panel_); + + esp_lcd_panel_init(panel_); + esp_lcd_panel_invert_color(panel_, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel_, DISPLAY_WIDTH, + DISPLAY_HEIGHT, DISPLAY_OFFSET_X, + DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + // 设置开机按钮的长按事件(直接进入配网模式) + boot_button_.OnLongPress([this]() { + // 唤醒电源保存定时器 + power_save_timer_->WakeUp(); + // 获取应用程序实例 + auto& app = Application::GetInstance(); + + // 进入配网模式 + app.SetDeviceState(kDeviceStateWifiConfiguring); + + // 重置WiFi配置以确保进入配网模式 + ResetWifiConfiguration(); + }); + + power_button_.OnClick([this]() { power_save_timer_->WakeUp(); }); + power_button_.OnLongPress([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() != kDeviceStateStarting && + !(power_manager_->IsCharging() && + power_manager_->GetBatteryLevel() < 100)) { + ESP_LOGI(TAG, "Power button long pressed, shutting down"); + esp_lcd_panel_disp_on_off(panel_, false); // 关闭显示 + rtc_gpio_set_level(POWER_CONTROL_PIN, 0); + rtc_gpio_hold_dis(POWER_CONTROL_PIN); + esp_deep_sleep_start(); + } + }); + } + + void InitializePowerCtl() { + ESP_LOGI(TAG, "Initialize Power Control GPIO"); + rtc_gpio_init(POWER_CONTROL_PIN); + rtc_gpio_set_direction(POWER_CONTROL_PIN, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(POWER_CONTROL_PIN, 1); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() {} + + public: + AIPILite() + : boot_button_(BOOT_BUTTON_GPIO), power_button_(POWER_BUTTON_GPIO) { + InitializePowerCtl(); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR, false); + return &audio_codec; + } + + virtual Display* GetDisplay() override { return display_; } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, + DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, + bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(AIPILite); diff --git a/main/boards/aipi-lite/config.h b/main/boards/aipi-lite/config.h new file mode 100644 index 0000000..22aef8e --- /dev/null +++ b/main/boards/aipi-lite/config.h @@ -0,0 +1,53 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// aipi-lite configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_6 // MCLK +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 // LRCK +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_14 // SCLK +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_13 // DIN +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 // DOUT + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_9 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_5 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_4 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_46 +#define BOOT_BUTTON_GPIO GPIO_NUM_42 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_3 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_16 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_17 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_15 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_7 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_18 +#define DISPLAY_SPI_MODE 0 +#define DISPLAY_SPI_SCLK_HZ (20 * 1000 * 1000) + +#define POWER_BUTTON_GPIO GPIO_NUM_1 +#define POWER_CONTROL_PIN GPIO_NUM_10 +#define POWER_CHARGE_DETECT_PIN GPIO_NUM_8 +#define POWER_ADC_UNIT ADC_UNIT_1 +#define POWER_ADC_CHANNEL ADC_CHANNEL_1 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/aipi-lite/config.json b/main/boards/aipi-lite/config.json new file mode 100644 index 0000000..9ea0168 --- /dev/null +++ b/main/boards/aipi-lite/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "aipi-lite", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_16MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/16m.csv\"" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/aipi-lite/config_en.json b/main/boards/aipi-lite/config_en.json new file mode 100644 index 0000000..6f71baf --- /dev/null +++ b/main/boards/aipi-lite/config_en.json @@ -0,0 +1,17 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "aipi-lite_en", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_16MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/16m.csv\"", + "CONFIG_LANGUAGE_EN_US=y", + "CONFIG_SR_WN_WN9_NIHAOXIAOZHI_TTS=n", + "CONFIG_SR_WN_WN9_JARVIS_TTS=y", + "CONFIG_SR_WN_WN9_SOPHIA_TTS=y" + ] + } + ] +} + diff --git a/main/boards/aipi-lite/power_manager.h b/main/boards/aipi-lite/power_manager.h new file mode 100644 index 0000000..e93b944 --- /dev/null +++ b/main/boards/aipi-lite/power_manager.h @@ -0,0 +1,187 @@ +#pragma once +#include +#include +#include + +#include +#include + +class PowerManager { + private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = POWER_CHARGE_DETECT_PIN; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick + // 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK( + adc_oneshot_read(adc_handle_, POWER_ADC_CHANNEL, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = {{1480, 0}, {1581, 20}, {1663, 40}, + {1750, 60}, {1840, 80}, {1980, 100}}; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && + average_adc < levels[i + 1].adc) { + float ratio = + static_cast(average_adc - levels[i].adc) / + (levels[i + 1].adc - levels[i].adc); + battery_level_ = + levels[i].level + + ratio * (levels[i + 1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", + adc_value, average_adc, battery_level_); + } + + public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = + [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 100000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel( + adc_handle_, POWER_ADC_CHANNEL, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { return battery_level_; } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/atk-dnesp32s3-box/atk_dnesp32s3_box.cc b/main/boards/atk-dnesp32s3-box/atk_dnesp32s3_box.cc new file mode 100644 index 0000000..1375949 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box/atk_dnesp32s3_box.cc @@ -0,0 +1,299 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" +#include "i2c_device.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define TAG "atk_dnesp32s3_box" + +class ATK_NoAudioCodecDuplex : public NoAudioCodec { +public: + ATK_NoAudioCodecDuplex(int input_sample_rate, int output_sample_rate, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + duplex_ = true; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + #ifdef I2S_HW_VERSION_2 + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + #endif + }, + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); + } +}; + +class XL9555_IN : public I2cDevice { +public: + XL9555_IN(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(0x06, 0x3B); + WriteReg(0x07, 0xFE); + } + + void xl9555_cfg(void) { + WriteReg(0x06, 0x1B); + WriteReg(0x07, 0xFE); + } + + void SetOutputState(uint8_t bit, uint8_t level) { + uint16_t data; + int index = bit; + + if (bit < 8) { + data = ReadReg(0x02); + } else { + data = ReadReg(0x03); + index -= 8; + } + + data = (data & ~(1 << index)) | (level << index); + + if (bit < 8) { + WriteReg(0x02, data); + } else { + WriteReg(0x03, data); + } + } + + int GetPingState(uint16_t pin) { + uint8_t data; + if (pin <= 0x0080) { + data = ReadReg(0x00); + return (data & (uint8_t)(pin & 0xFF)) ? 1 : 0; + } else { + data = ReadReg(0x01); + return (data & (uint8_t)((pin >> 8) & 0xFF )) ? 1 : 0; + } + + return 0; + } +}; + +class atk_dnesp32s3_box : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + i2c_master_dev_handle_t xl9555_handle_; + Button boot_button_; + LcdDisplay* display_; + XL9555_IN* xl9555_in_; + bool es8311_detected_ = false; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = GPIO_NUM_48, + .scl_io_num = GPIO_NUM_45, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + // Initialize XL9555 + xl9555_in_ = new XL9555_IN(i2c_bus_, 0x20); + + if (xl9555_in_->GetPingState(0x0020) == 1) { + es8311_detected_ = true; /* 音频设备标志位,SPK_CTRL_IO为高电平时,该标志位置1,且判定为ES8311 */ + } else { + es8311_detected_ = false; /* 音频设备标志位,SPK_CTRL_IO为低电平时,该标志位置0,且判定为NS4168 */ + } + + xl9555_in_->xl9555_cfg(); + } + + void InitializeATK_ST7789_80_Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + /* 配置RD引脚 */ + gpio_config_t gpio_init_struct; + gpio_init_struct.intr_type = GPIO_INTR_DISABLE; + gpio_init_struct.mode = GPIO_MODE_INPUT_OUTPUT; + gpio_init_struct.pin_bit_mask = 1ull << LCD_NUM_RD; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&gpio_init_struct); + gpio_set_level(LCD_NUM_RD, 1); + + esp_lcd_i80_bus_handle_t i80_bus = NULL; + esp_lcd_i80_bus_config_t bus_config = { + .dc_gpio_num = LCD_NUM_DC, + .wr_gpio_num = LCD_NUM_WR, + .clk_src = LCD_CLK_SRC_DEFAULT, + .data_gpio_nums = { + GPIO_LCD_D0, + GPIO_LCD_D1, + GPIO_LCD_D2, + GPIO_LCD_D3, + GPIO_LCD_D4, + GPIO_LCD_D5, + GPIO_LCD_D6, + GPIO_LCD_D7, + }, + .bus_width = 8, + .max_transfer_bytes = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t), + .psram_trans_align = 64, + .sram_trans_align = 4, + }; + ESP_ERROR_CHECK(esp_lcd_new_i80_bus(&bus_config, &i80_bus)); + + esp_lcd_panel_io_i80_config_t io_config = { + .cs_gpio_num = LCD_NUM_CS, + .pclk_hz = (10 * 1000 * 1000), + .trans_queue_depth = 10, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .dc_levels = { + .dc_idle_level = 0, + .dc_cmd_level = 0, + .dc_dummy_level = 0, + .dc_data_level = 1, + }, + .flags = { + .swap_color_bytes = 0, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i80(i80_bus, &io_config, &panel_io)); + + esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = LCD_NUM_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_set_gap(panel, 0, 0); + uint8_t data0[] = {0x00}; + uint8_t data1[] = {0x65}; + esp_lcd_panel_io_tx_param(panel_io, 0x36, data0, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x3A, data1, 1); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + atk_dnesp32s3_box() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeATK_ST7789_80_Display(); + xl9555_in_->SetOutputState(5, 1); + xl9555_in_->SetOutputState(7, 1); + InitializeButtons(); + } + + virtual AudioCodec* GetAudioCodec() override { + /* 根据探测结果初始化编解码器 */ + if (es8311_detected_) { + /* 使用ES8311 驱动 */ + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + GPIO_NUM_NC, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } else { + static ATK_NoAudioCodecDuplex audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN); + return &audio_codec; + } + return NULL; + } + + virtual Display* GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(atk_dnesp32s3_box); diff --git a/main/boards/atk-dnesp32s3-box/config.h b/main/boards/atk-dnesp32s3-box/config.h new file mode 100644 index 0000000..4b8e002 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box/config.h @@ -0,0 +1,46 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_13 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_21 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_47 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_4 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY true +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + +// Pin Definitions +#define LCD_NUM_CS GPIO_NUM_1 +#define LCD_NUM_DC GPIO_NUM_2 +#define LCD_NUM_RD GPIO_NUM_41 +#define LCD_NUM_WR GPIO_NUM_42 +#define LCD_NUM_RST GPIO_NUM_NC + +#define GPIO_LCD_D0 GPIO_NUM_40 +#define GPIO_LCD_D1 GPIO_NUM_39 +#define GPIO_LCD_D2 GPIO_NUM_38 +#define GPIO_LCD_D3 GPIO_NUM_12 +#define GPIO_LCD_D4 GPIO_NUM_11 +#define GPIO_LCD_D5 GPIO_NUM_10 +#define GPIO_LCD_D6 GPIO_NUM_9 +#define GPIO_LCD_D7 GPIO_NUM_46 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/atk-dnesp32s3-box/config.json b/main/boards/atk-dnesp32s3-box/config.json new file mode 100644 index 0000000..21e97d3 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atk-dnesp32s3-box", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/atk-dnesp32s3-box0/atk_dnesp32s3_box0.cc b/main/boards/atk-dnesp32s3-box0/atk_dnesp32s3_box0.cc new file mode 100644 index 0000000..ce0bc43 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box0/atk_dnesp32s3_box0.cc @@ -0,0 +1,388 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include "i2c_device.h" +#include +#include +#include + +#include +#include + +#define TAG "atk_dnesp32s3_box0" + +class atk_dnesp32s3_box0 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button right_button_; + Button left_button_; + Button middle_button_; + LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + PowerSupply power_status_; + LcdStatus LcdStatus_ = kDevicelcdbacklightOn; + PowerSleep power_sleep_ = kDeviceNoSleep; + WakeStatus wake_status_ = kDeviceAwakened; + XiaozhiStatus XiaozhiStatus_ = kDevice_Exit_Distributionnetwork; + esp_timer_handle_t wake_timer_handle_; + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + int ticks_ = 0; + const int kChgCtrlInterval = 5; + + void InitializeBoardPowerManager() { + gpio_config_t gpio_init_struct = {0}; + gpio_init_struct.intr_type = GPIO_INTR_DISABLE; + gpio_init_struct.mode = GPIO_MODE_INPUT_OUTPUT; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pin_bit_mask = (1ull << CODEC_PWR_PIN) | (1ull << SYS_POW_PIN); + gpio_config(&gpio_init_struct); + + gpio_set_level(CODEC_PWR_PIN, 1); + gpio_set_level(SYS_POW_PIN, 1); + + gpio_config_t chg_init_struct = {0}; + + chg_init_struct.intr_type = GPIO_INTR_DISABLE; + chg_init_struct.mode = GPIO_MODE_INPUT; + chg_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + chg_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + chg_init_struct.pin_bit_mask = 1ull << CHRG_PIN; + ESP_ERROR_CHECK(gpio_config(&chg_init_struct)); + + chg_init_struct.mode = GPIO_MODE_OUTPUT; + chg_init_struct.pull_up_en = GPIO_PULLUP_DISABLE; + chg_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + chg_init_struct.pin_bit_mask = 1ull << CHG_CTRL_PIN; + ESP_ERROR_CHECK(gpio_config(&chg_init_struct)); + gpio_set_level(CHG_CTRL_PIN, 1); + + if (gpio_get_level(CHRG_PIN) == 0) { + power_status_ = kDeviceTypecSupply; + } else { + power_status_ = kDeviceBatterySupply; + } + + esp_timer_create_args_t wake_display_timer_args = { + .callback = [](void *arg) { + atk_dnesp32s3_box0* self = static_cast(arg); + if (self->LcdStatus_ == kDevicelcdbacklightOff && Application::GetInstance().GetDeviceState() == kDeviceStateListening + && self->wake_status_ == kDeviceWaitWake) { + + if (self->power_sleep_ == kDeviceNeutralSleep) { + self->power_save_timer_->WakeUp(); + } + + self->GetBacklight()->RestoreBrightness(); + self->wake_status_ = kDeviceAwakened; + self->LcdStatus_ = kDevicelcdbacklightOn; + } else if (self->power_sleep_ == kDeviceNeutralSleep && Application::GetInstance().GetDeviceState() == kDeviceStateListening + && self->LcdStatus_ != kDevicelcdbacklightOff && self->wake_status_ == kDeviceAwakened) { + self->power_save_timer_->WakeUp(); + self->power_sleep_ = kDeviceNoSleep; + } else { + self->ticks_ ++; + if (self->ticks_ % self->kChgCtrlInterval == 0) { + if (gpio_get_level(CHRG_PIN) == 0) { + self->power_status_ = kDeviceTypecSupply; + } else { + self->power_status_ = kDeviceBatterySupply; + } + + if (self->power_manager_->low_voltage_ < 2877 && self->power_status_ != kDeviceTypecSupply) { + esp_timer_stop(self->power_manager_->timer_handle_); + gpio_set_level(CHG_CTRL_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + gpio_set_level(SYS_POW_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + } + } + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "wake_update_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&wake_display_timer_args, &wake_timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(wake_timer_handle_, 300000)); + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(CHRG_PIN); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + power_sleep_ = kDeviceNeutralSleep; + XiaozhiStatus_ = kDevice_join_Sleep; + GetDisplay()->SetPowerSaveMode(true); + + if (LcdStatus_ != kDevicelcdbacklightOff) { + GetBacklight()->SetBrightness(1); + } + }); + power_save_timer_->OnExitSleepMode([this]() { + power_sleep_ = kDeviceNoSleep; + GetDisplay()->SetPowerSaveMode(false); + + if (XiaozhiStatus_ != kDevice_Exit_Sleep) { + GetBacklight()->RestoreBrightness(); + } + }); + power_save_timer_->OnShutdownRequest([this]() { + if (power_status_ == kDeviceBatterySupply) { + esp_timer_stop(power_manager_->timer_handle_); + gpio_set_level(CHG_CTRL_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + gpio_set_level(SYS_POW_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + }); + + power_save_timer_->SetEnabled(true); + } + + // Initialize I2C peripheral + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + middle_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + + if (LcdStatus_ != kDevicelcdbacklightOff) { + if (power_sleep_ == kDeviceNeutralSleep) { + power_save_timer_->WakeUp(); + power_sleep_ = kDeviceNoSleep; + } + + app.ToggleChatState(); + } + }); + + middle_button_.OnPressUp([this]() { + if (LcdStatus_ == kDevicelcdbacklightOff) { + Application::GetInstance().StopListening(); + Application::GetInstance().SetDeviceState(kDeviceStateIdle); + wake_status_ = kDeviceWaitWake; + } + + if (XiaozhiStatus_ == kDevice_Distributionnetwork || XiaozhiStatus_ == kDevice_Exit_Sleep) { + esp_timer_stop(power_manager_->timer_handle_); + gpio_set_level(CHG_CTRL_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + gpio_set_level(SYS_POW_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } else if (XiaozhiStatus_ == kDevice_join_Sleep) { + GetBacklight()->RestoreBrightness(); + XiaozhiStatus_ = kDevice_null; + } + }); + + middle_button_.OnLongPress([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + + if (app.GetDeviceState() != kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + if (app.GetDeviceState() == kDeviceStateWifiConfiguring && power_status_ != kDeviceTypecSupply) { + GetBacklight()->SetBrightness(0); + XiaozhiStatus_ = kDevice_Distributionnetwork; + } else if (power_status_ == kDeviceBatterySupply && LcdStatus_ != kDevicelcdbacklightOff) { + Application::GetInstance().StartListening(); + GetBacklight()->SetBrightness(0); + XiaozhiStatus_ = kDevice_Exit_Sleep; + } else if (power_status_ == kDeviceTypecSupply && LcdStatus_ == kDevicelcdbacklightOn && Application::GetInstance().GetDeviceState() != kDeviceStateStarting) { + Application::GetInstance().StartListening(); + GetBacklight()->SetBrightness(0); + LcdStatus_ = kDevicelcdbacklightOff; + } else if (LcdStatus_ == kDevicelcdbacklightOff && (power_status_ == kDeviceTypecSupply || power_status_ == kDeviceBatterySupply)) { + GetDisplay()->SetChatMessage("system", ""); + GetBacklight()->RestoreBrightness(); + wake_status_ = kDeviceAwakened; + LcdStatus_ = kDevicelcdbacklightOn; + } + } + }); + + left_button_.OnClick([this]() { + if (power_sleep_ == kDeviceNeutralSleep && LcdStatus_ != kDevicelcdbacklightOff) { + power_save_timer_->WakeUp(); + power_sleep_ = kDeviceNoSleep; + } + + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + left_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + right_button_.OnClick([this]() { + if (power_sleep_ == kDeviceNeutralSleep && LcdStatus_ != kDevicelcdbacklightOff) { + power_save_timer_->WakeUp(); + power_sleep_ = kDeviceNoSleep; + } + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + right_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + } + + void InitializeSt7789Display() { + ESP_LOGI(TAG, "Install panel IO"); + + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io); + + ESP_LOGI(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG, + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_init(panel); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + atk_dnesp32s3_box0() : + right_button_(R_BUTTON_GPIO, false), + left_button_(L_BUTTON_GPIO, false), + middle_button_(M_BUTTON_GPIO, true) { + InitializeBoardPowerManager(); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + GPIO_NUM_NC, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(atk_dnesp32s3_box0); diff --git a/main/boards/atk-dnesp32s3-box0/config.h b/main/boards/atk-dnesp32s3-box0/config.h new file mode 100644 index 0000000..f2c940e --- /dev/null +++ b/main/boards/atk-dnesp32s3-box0/config.h @@ -0,0 +1,84 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +enum XiaozhiStatus { + kDevice_null, + kDevice_join_Sleep, + kDevice_Exit_Sleep, + kDevice_Distributionnetwork, + kDevice_Exit_Distributionnetwork, +}; + +enum LcdStatus { + kDevicelcdbacklightOn, + kDevicelcdbacklightOff, +}; + +enum WakeStatus { + kDeviceAwakened, + kDeviceWaitWake, + kDeviceSleeped, +}; + +enum PowerSupply { + kDeviceTypecSupply, + kDeviceBatterySupply, +}; + +enum PowerSleep { + kDeviceNoSleep, + kDeviceDeepSleep, + kDeviceNeutralSleep, +}; + +#define SYS_POW_PIN GPIO_NUM_2 +#define CHG_CTRL_PIN GPIO_NUM_47 +#define CODEC_PWR_PIN GPIO_NUM_14 +#define CHRG_PIN GPIO_NUM_48 + +#define BAT_VSEN_PIN GPIO_NUM_1 + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_11 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_12 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define AUDIO_SPK_GPIO_PIN GPIO_NUM_21 + +#define R_BUTTON_GPIO GPIO_NUM_0 +#define M_BUTTON_GPIO GPIO_NUM_4 +#define L_BUTTON_GPIO GPIO_NUM_3 + +#define BUILTIN_LED_GPIO GPIO_NUM_13 + +#define LCD_SCLK_PIN GPIO_NUM_39 +#define LCD_MOSI_PIN GPIO_NUM_40 +#define LCD_MISO_PIN GPIO_NUM_NC +#define LCD_DC_PIN GPIO_NUM_38 +#define LCD_CS_PIN GPIO_NUM_41 +#define LCD_RST_PIN GPIO_NUM_NC + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_42 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atk-dnesp32s3-box0/config.json b/main/boards/atk-dnesp32s3-box0/config.json new file mode 100644 index 0000000..20849d4 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box0/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atk-dnesp32s3-box0", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/atk-dnesp32s3-box0/power_manager.h b/main/boards/atk-dnesp32s3-box0/power_manager.h new file mode 100644 index 0000000..e9a206c --- /dev/null +++ b/main/boards/atk-dnesp32s3-box0/power_manager.h @@ -0,0 +1,193 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 0; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + uint32_t temp_val = 0; + + gpio_set_level(CHG_CTRL_PIN, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + + for(int t = 0; t < 10; t ++) { + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); + temp_val += adc_value; + } + + gpio_set_level(CHG_CTRL_PIN, 1); + vTaskDelay(pdMS_TO_TICKS(100)); + + adc_value = temp_val / 10; + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {2951, 0}, /* 3.80V */ + {3019, 20}, + {3037, 40}, + {3091, 60}, /* 3.88 */ + {3124, 80}, + {3231, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + low_voltage_ = adc_value; + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + esp_timer_handle_t timer_handle_; + uint16_t low_voltage_ = 2877; + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/atk-dnesp32s3-box2-4g/atk_dnesp32s3_box2.cc b/main/boards/atk-dnesp32s3-box2-4g/atk_dnesp32s3_box2.cc new file mode 100644 index 0000000..4a906db --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-4g/atk_dnesp32s3_box2.cc @@ -0,0 +1,477 @@ +#include "dual_network_board.h" +#include "codecs/es8389_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include "i2c_device.h" +#include +#include +#include + +#include +#include +#include "esp_io_expander_tca95xx_16bit.h" + +#define TAG "atk_dnesp32s3_box2_4g" + +class atk_dnesp32s3_box2_4g : public DualNetworkBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + LcdDisplay* display_; + esp_io_expander_handle_t io_exp_handle; + button_handle_t btns; + button_driver_t* btn_driver_ = nullptr; + static atk_dnesp32s3_box2_4g* instance_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + PowerSupply power_status_; + esp_timer_handle_t wake_timer_handle_; + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + int ticks_ = 0; + const int kChgCtrlInterval = 5; + + void InitializeBoardPowerManager() { + instance_ = this; + + if (IoExpanderGetLevel(XIO_CHRG) == 0) { + power_status_ = kDeviceTypecSupply; + } else { + power_status_ = kDeviceBatterySupply; + } + + esp_timer_create_args_t wake_display_timer_args = { + .callback = [](void *arg) { + atk_dnesp32s3_box2_4g* self = static_cast(arg); + + self->ticks_ ++; + if (self->ticks_ % self->kChgCtrlInterval == 0) { + if (self->IoExpanderGetLevel(XIO_CHRG) == 0) { + self->power_status_ = kDeviceTypecSupply; + } else { + self->power_status_ = kDeviceBatterySupply; + } + + /* 低于某个电量,会自动关机 */ + if (self->power_manager_->low_voltage_ < 2630 && self->power_status_ == kDeviceBatterySupply) { + esp_timer_stop(self->power_manager_->timer_handle_); + + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_INPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + } + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "wake_update_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&wake_display_timer_args, &wake_timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(wake_timer_handle_, 100000)); + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(io_exp_handle); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + if (power_status_ == kDeviceBatterySupply) { + GetBacklight()->SetBrightness(0); + esp_timer_stop(power_manager_->timer_handle_); + esp_io_expander_set_dir( io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_io_expander_set_level(io_exp_handle, XIO_SYS_POW, 0); + } + }); + + power_save_timer_->SetEnabled(true); + } + + void audio_volume_change(bool direction) { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume(); + + if (direction) { + volume += 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + } else { + volume -= 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + } + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + } + + void audio_volume_minimum(){ + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + } + + void audio_volume_maxmum(){ + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + } + + esp_err_t IoExpanderSetLevel(uint16_t pin_mask, uint8_t level) { + return esp_io_expander_set_level(io_exp_handle, pin_mask, level); + } + + uint8_t IoExpanderGetLevel(uint16_t pin_mask) { + uint32_t pin_val = 0; + esp_io_expander_get_level(io_exp_handle, DRV_IO_EXP_INPUT_MASK, &pin_val); + pin_mask &= DRV_IO_EXP_INPUT_MASK; + return (uint8_t)((pin_val & pin_mask) ? 1 : 0); + } + + void InitializeIoExpander() { + esp_err_t ret = ESP_OK; + esp_io_expander_new_i2c_tca95xx_16bit(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_000, &io_exp_handle); + + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_OUTPUT_MASK, IO_EXPANDER_OUTPUT); + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_INPUT_MASK, IO_EXPANDER_INPUT); + + ret |= esp_io_expander_set_level(io_exp_handle, XIO_SYS_POW, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_EN_3V3A, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_EN_4G, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_SPK_EN, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_USB_SEL, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_VBUS_EN, 0); + + assert(ret == ESP_OK); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeButtons() { + instance_ = this; + + button_config_t l_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_config_t m_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_config_t r_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_driver_t* xio_l_btn_driver_ = nullptr; + button_driver_t* xio_m_btn_driver_ = nullptr; + + button_handle_t l_btn_handle = NULL; + button_handle_t m_btn_handle = NULL; + button_handle_t r_btn_handle = NULL; + + xio_l_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + xio_l_btn_driver_->enable_power_save = false; + xio_l_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !instance_->IoExpanderGetLevel(XIO_KEY_L); + }; + ESP_ERROR_CHECK(iot_button_create(&l_btn_cfg, xio_l_btn_driver_, &l_btn_handle)); + + xio_m_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + xio_m_btn_driver_->enable_power_save = false; + xio_m_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return instance_->IoExpanderGetLevel(XIO_KEY_M); + }; + ESP_ERROR_CHECK(iot_button_create(&m_btn_cfg, xio_m_btn_driver_, &m_btn_handle)); + + button_gpio_config_t r_cfg = { + .gpio_num = R_BUTTON_GPIO, + .active_level = BUTTON_INACTIVE, + .enable_power_save = false, + .disable_pull = false + }; + ESP_ERROR_CHECK(iot_button_new_gpio_device(&r_btn_cfg, &r_cfg, &r_btn_handle)); + + iot_button_register_cb(l_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_change(false); + }, this); + + iot_button_register_cb(l_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_minimum(); + }, this); + + iot_button_register_cb(m_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (self->GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + } + else { + app.ToggleChatState(); + } + } else { + app.ToggleChatState(); + } + }, this); + + iot_button_register_cb(m_btn_handle, BUTTON_DOUBLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + self->SwitchNetworkType(); + } + }, this); + + iot_button_register_cb(m_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + + auto& app = Application::GetInstance(); + if (self->GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + auto& wifi_board = static_cast(self->GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + + if (self->power_status_ == kDeviceBatterySupply) { + auto backlight = Board::GetInstance().GetBacklight(); + backlight->SetBrightness(0); + esp_timer_stop(self->power_manager_->timer_handle_); + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_io_expander_set_level(self->io_exp_handle, XIO_SYS_POW, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + }, this); + + iot_button_register_cb(r_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_change(true); + }, this); + + iot_button_register_cb(r_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_maxmum(); + }, this); + } + + void InitializeSt7789Display() { + ESP_LOGI(TAG, "Install panel IO"); + + /*RD PIN */ + gpio_config_t gpio_init_struct; + gpio_init_struct.intr_type = GPIO_INTR_DISABLE; + gpio_init_struct.mode = GPIO_MODE_INPUT_OUTPUT; + gpio_init_struct.pin_bit_mask = 1ull << LCD_PIN_RD; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&gpio_init_struct); + gpio_set_level(LCD_PIN_RD, 1); + + /* BL PIN */ + gpio_init_struct.pin_bit_mask = 1ull << DISPLAY_BACKLIGHT_PIN; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&gpio_init_struct); + + esp_lcd_i80_bus_handle_t i80_bus = NULL; + esp_lcd_i80_bus_config_t bus_config = { + .dc_gpio_num = LCD_PIN_DC, + .wr_gpio_num = LCD_PIN_WR, + .clk_src = LCD_CLK_SRC_DEFAULT, + .data_gpio_nums = { + LCD_PIN_D0, + LCD_PIN_D1, + LCD_PIN_D2, + LCD_PIN_D3, + LCD_PIN_D4, + LCD_PIN_D5, + LCD_PIN_D6, + LCD_PIN_D7, + }, + .bus_width = 8, + .max_transfer_bytes = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t), + .psram_trans_align = 64, + .sram_trans_align = 4, + }; + ESP_ERROR_CHECK(esp_lcd_new_i80_bus(&bus_config, &i80_bus)); + + esp_lcd_panel_io_i80_config_t io_config = { + .cs_gpio_num = LCD_PIN_CS, + .pclk_hz = (20 * 1000 * 1000), + .trans_queue_depth = 7, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .dc_levels = { + .dc_idle_level = 1, + .dc_cmd_level = 0, + .dc_dummy_level = 0, + .dc_data_level = 1, + }, + .flags = { + .cs_active_high = 0, + .pclk_active_neg = 0, + .pclk_idle_low = 0, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i80(i80_bus, &io_config, &panel_io)); + + esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = LCD_PIN_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_set_gap(panel, 0, 0); + esp_lcd_panel_io_tx_param(panel_io, 0xCF, (uint8_t[]) {0x00,0x83,0x30}, 3); + esp_lcd_panel_io_tx_param(panel_io, 0xED, (uint8_t[]) {0x64,0x03,0x12,0x81}, 4); + esp_lcd_panel_io_tx_param(panel_io, 0xE8, (uint8_t[]) {0x85,0x01,0x79}, 3); + esp_lcd_panel_io_tx_param(panel_io, 0xCB, (uint8_t[]) {0x39,0x2C,0x00,0x34,0x02}, 5); + esp_lcd_panel_io_tx_param(panel_io, 0xF7, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xEA, (uint8_t[]) {0x00,0x00}, 2); + esp_lcd_panel_io_tx_param(panel_io, 0xbb, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xc3, (uint8_t[]) {0x00}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC4, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC5, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC6, (uint8_t[]) {0x10}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC7, (uint8_t[]) {0xB0}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x36, (uint8_t[]) {0x60}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x3A, (uint8_t[]) {0x55}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xB1, (uint8_t[]) {0x00,0x1B}, 2); + esp_lcd_panel_io_tx_param(panel_io, 0xF2, (uint8_t[]) {0x08}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x26, (uint8_t[]) {0x01}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xE0, (uint8_t[]) {0xD0,0x00,0x02,0x07,0x0A,0x28,0x32,0x44,0x42,0x06,0x0E,0x12,0x14,0x17}, 14); + esp_lcd_panel_io_tx_param(panel_io, 0xE1, (uint8_t[]) {0xD0,0x00,0x02,0x07,0x0A,0x28,0x31,0x54,0x47,0x0E,0x1C,0x17,0x1B,0x1E}, 14); + esp_lcd_panel_io_tx_param(panel_io, 0xB7, (uint8_t[]) {0x07}, 1); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + atk_dnesp32s3_box2_4g() : + DualNetworkBoard(Module_4G_TX_PIN, Module_4G_RX_PIN) { + InitializeI2c(); + InitializeIoExpander(); + InitializePowerSaveTimer(); + InitializePowerManager(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + InitializeBoardPowerManager(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8389AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8389_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(atk_dnesp32s3_box2_4g); + +// 定义静态成员变量 +atk_dnesp32s3_box2_4g* atk_dnesp32s3_box2_4g::instance_ = nullptr; diff --git a/main/boards/atk-dnesp32s3-box2-4g/config.h b/main/boards/atk-dnesp32s3-box2-4g/config.h new file mode 100644 index 0000000..70e9d4d --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-4g/config.h @@ -0,0 +1,80 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +enum PowerSupply { + kDeviceTypecSupply, + kDeviceBatterySupply, +}; + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_42 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_41 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_48 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_47 +#define AUDIO_CODEC_ES8389_ADDR ES8389_CODEC_DEFAULT_ADDR + +#define SPISD_PIN_MOSI GPIO_NUM_16 +#define SPISD_PIN_MISO GPIO_NUM_18 +#define SPISD_PIN_CLK GPIO_NUM_17 +#define SPISD_PIN_TS GPIO_NUM_15 + +#define R_BUTTON_GPIO GPIO_NUM_0 + +#define XL9555_INT_GPIO GPIO_NUM_2 +#define XIO_IO_SBU2 (IO_EXPANDER_PIN_NUM_3) +#define XIO_IO_SBU1 (IO_EXPANDER_PIN_NUM_4) +#define XIO_KEY_L (IO_EXPANDER_PIN_NUM_5) +#define XIO_KEY_Q (IO_EXPANDER_PIN_NUM_6) +#define XIO_KEY_M (IO_EXPANDER_PIN_NUM_7) +#define XIO_USB_SEL (IO_EXPANDER_PIN_NUM_8) +#define XIO_SPK_EN (IO_EXPANDER_PIN_NUM_9) +#define XIO_SYS_POW (IO_EXPANDER_PIN_NUM_10) +#define XIO_VBUS_EN (IO_EXPANDER_PIN_NUM_11) +#define XIO_EN_4G (IO_EXPANDER_PIN_NUM_12) +#define XIO_EN_3V3A (IO_EXPANDER_PIN_NUM_13) +#define XIO_CHG_CTRL (IO_EXPANDER_PIN_NUM_14) +#define XIO_CHRG (IO_EXPANDER_PIN_NUM_15) + +#define DRV_IO_EXP_OUTPUT_MASK 0x3F18 +#define DRV_IO_EXP_INPUT_MASK 0xC0E7 + +#define LCD_PIN_CS GPIO_NUM_14 +#define LCD_PIN_DC GPIO_NUM_12 +#define LCD_PIN_RD GPIO_NUM_10 +#define LCD_PIN_WR GPIO_NUM_11 +#define LCD_PIN_RST GPIO_NUM_NC +#define LCD_PIN_D0 GPIO_NUM_13 +#define LCD_PIN_D1 GPIO_NUM_9 +#define LCD_PIN_D2 GPIO_NUM_8 +#define LCD_PIN_D3 GPIO_NUM_7 +#define LCD_PIN_D4 GPIO_NUM_6 +#define LCD_PIN_D5 GPIO_NUM_5 +#define LCD_PIN_D6 GPIO_NUM_4 +#define LCD_PIN_D7 GPIO_NUM_3 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_21 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define Module_4G_RX_PIN GPIO_NUM_44 +#define Module_4G_TX_PIN GPIO_NUM_43 + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atk-dnesp32s3-box2-4g/config.json b/main/boards/atk-dnesp32s3-box2-4g/config.json new file mode 100644 index 0000000..076253a --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-4g/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atk-dnesp32s3-box2-4g", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/atk-dnesp32s3-box2-4g/power_manager.h b/main/boards/atk-dnesp32s3-box2-4g/power_manager.h new file mode 100644 index 0000000..103ce88 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-4g/power_manager.h @@ -0,0 +1,195 @@ +#pragma once +#include +#include +#include "esp_io_expander_tca95xx_16bit.h" +#include +#include +#include + + +class PowerManager { +private: + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + esp_io_expander_handle_t xl9555_; + uint32_t pin_val = 0; + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + esp_io_expander_get_level(xl9555_, DRV_IO_EXP_INPUT_MASK, &pin_val); + bool new_charging_status = ((uint8_t)((pin_val & XIO_CHRG) ? 1 : 0)) == 0; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + uint32_t temp_val = 0; + + esp_io_expander_set_dir(xl9555_, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(xl9555_, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(500)); + + for(int t = 0; t < 10; t ++) { + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); + temp_val += adc_value; + } + + esp_io_expander_set_dir(xl9555_, XIO_CHG_CTRL, IO_EXPANDER_INPUT); + + adc_value = temp_val / 10; + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {2696, 0}, /* 3.48V -屏幕闪屏 */ + {2724, 20}, /* 3.53V */ + {2861, 40}, /* 3.7V */ + {3038, 60}, /* 3.90V */ + {3150, 80}, /* 4.02V */ + {3280, 100} /* 4.14V */ + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + low_voltage_ = adc_value; + + // ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + esp_timer_handle_t timer_handle_; + uint16_t low_voltage_ = 2630; + PowerManager(esp_io_expander_handle_t xl9555) : xl9555_(xl9555) { + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/atk-dnesp32s3-box2-wifi/atk_dnesp32s3_box2.cc b/main/boards/atk-dnesp32s3-box2-wifi/atk_dnesp32s3_box2.cc new file mode 100644 index 0000000..acc2e21 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-wifi/atk_dnesp32s3_box2.cc @@ -0,0 +1,456 @@ +#include "wifi_board.h" +#include "codecs/es8389_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include "i2c_device.h" +#include +#include +#include + +#include +#include +#include "esp_io_expander_tca95xx_16bit.h" + +#define TAG "atk_dnesp32s3_box2_wifi" + +class atk_dnesp32s3_box2_wifi : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + LcdDisplay* display_; + esp_io_expander_handle_t io_exp_handle; + button_handle_t btns; + button_driver_t* btn_driver_ = nullptr; + static atk_dnesp32s3_box2_wifi* instance_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + PowerSupply power_status_; + esp_timer_handle_t wake_timer_handle_; + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + int ticks_ = 0; + const int kChgCtrlInterval = 5; + + void InitializeBoardPowerManager() { + instance_ = this; + + if (IoExpanderGetLevel(XIO_CHRG) == 0) { + power_status_ = kDeviceTypecSupply; + } else { + power_status_ = kDeviceBatterySupply; + } + + esp_timer_create_args_t wake_display_timer_args = { + .callback = [](void *arg) { + atk_dnesp32s3_box2_wifi* self = static_cast(arg); + + self->ticks_ ++; + if (self->ticks_ % self->kChgCtrlInterval == 0) { + if (self->IoExpanderGetLevel(XIO_CHRG) == 0) { + self->power_status_ = kDeviceTypecSupply; + } else { + self->power_status_ = kDeviceBatterySupply; + } + + /* 低于某个电量,会自动关机 */ + if (self->power_manager_->low_voltage_ < 2630 && self->power_status_ == kDeviceBatterySupply) { + esp_timer_stop(self->power_manager_->timer_handle_); + + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_INPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + } + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "wake_update_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&wake_display_timer_args, &wake_timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(wake_timer_handle_, 100000)); + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(io_exp_handle); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + if (power_status_ == kDeviceBatterySupply) { + GetBacklight()->SetBrightness(0); + esp_timer_stop(power_manager_->timer_handle_); + esp_io_expander_set_dir( io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_io_expander_set_level(io_exp_handle, XIO_SYS_POW, 0); + } + }); + + power_save_timer_->SetEnabled(true); + } + + void audio_volume_change(bool direction) { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume(); + + if (direction) { + volume += 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + } else { + volume -= 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + } + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + } + + void audio_volume_minimum(){ + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + } + + void audio_volume_maxmum(){ + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + } + + esp_err_t IoExpanderSetLevel(uint16_t pin_mask, uint8_t level) { + return esp_io_expander_set_level(io_exp_handle, pin_mask, level); + } + + uint8_t IoExpanderGetLevel(uint16_t pin_mask) { + uint32_t pin_val = 0; + esp_io_expander_get_level(io_exp_handle, DRV_IO_EXP_INPUT_MASK, &pin_val); + pin_mask &= DRV_IO_EXP_INPUT_MASK; + return (uint8_t)((pin_val & pin_mask) ? 1 : 0); + } + + void InitializeIoExpander() { + esp_err_t ret = ESP_OK; + esp_io_expander_new_i2c_tca95xx_16bit(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_000, &io_exp_handle); + + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_OUTPUT_MASK, IO_EXPANDER_OUTPUT); + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_INPUT_MASK, IO_EXPANDER_INPUT); + + ret |= esp_io_expander_set_level(io_exp_handle, XIO_SYS_POW, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_EN_3V3A, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_EN_4G, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_SPK_EN, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_USB_SEL, 1); + ret |= esp_io_expander_set_level(io_exp_handle, XIO_VBUS_EN, 0); + + assert(ret == ESP_OK); + } + + // Initialize I2C peripheral + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeButtons() { + instance_ = this; + + button_config_t l_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_config_t m_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_config_t r_btn_cfg = { + .long_press_time = 800, + .short_press_time = 500 + }; + + button_driver_t* xio_l_btn_driver_ = nullptr; + button_driver_t* xio_m_btn_driver_ = nullptr; + + button_handle_t l_btn_handle = NULL; + button_handle_t m_btn_handle = NULL; + button_handle_t r_btn_handle = NULL; + + xio_l_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + xio_l_btn_driver_->enable_power_save = false; + xio_l_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !instance_->IoExpanderGetLevel(XIO_KEY_L); + }; + ESP_ERROR_CHECK(iot_button_create(&l_btn_cfg, xio_l_btn_driver_, &l_btn_handle)); + + xio_m_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + xio_m_btn_driver_->enable_power_save = false; + xio_m_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return instance_->IoExpanderGetLevel(XIO_KEY_M); + }; + ESP_ERROR_CHECK(iot_button_create(&m_btn_cfg, xio_m_btn_driver_, &m_btn_handle)); + + button_gpio_config_t r_cfg = { + .gpio_num = R_BUTTON_GPIO, + .active_level = BUTTON_INACTIVE, + .enable_power_save = false, + .disable_pull = false + }; + ESP_ERROR_CHECK(iot_button_new_gpio_device(&r_btn_cfg, &r_cfg, &r_btn_handle)); + + iot_button_register_cb(l_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_change(false); + }, this); + + iot_button_register_cb(l_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_minimum(); + }, this); + + iot_button_register_cb(m_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + app.ToggleChatState(); + }, this); + + iot_button_register_cb(m_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + + if (self->power_status_ == kDeviceBatterySupply) { + auto backlight = Board::GetInstance().GetBacklight(); + backlight->SetBrightness(0); + esp_timer_stop(self->power_manager_->timer_handle_); + esp_io_expander_set_dir(self->io_exp_handle, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(self->io_exp_handle, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_io_expander_set_level(self->io_exp_handle, XIO_SYS_POW, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + } + }, this); + + iot_button_register_cb(r_btn_handle, BUTTON_PRESS_DOWN, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_change(true); + }, this); + + iot_button_register_cb(r_btn_handle, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->power_save_timer_->WakeUp(); + self->audio_volume_maxmum(); + }, this); + } + + void InitializeSt7789Display() { + ESP_LOGI(TAG, "Install panel IO"); + + /* RD PIN */ + gpio_config_t gpio_init_struct; + gpio_init_struct.intr_type = GPIO_INTR_DISABLE; + gpio_init_struct.mode = GPIO_MODE_INPUT_OUTPUT; + gpio_init_struct.pin_bit_mask = 1ull << LCD_PIN_RD; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&gpio_init_struct); + gpio_set_level(LCD_PIN_RD, 1); + + /* BL PIN */ + gpio_init_struct.pin_bit_mask = 1ull << DISPLAY_BACKLIGHT_PIN; + gpio_init_struct.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_init_struct.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&gpio_init_struct); + + esp_lcd_i80_bus_handle_t i80_bus = NULL; + esp_lcd_i80_bus_config_t bus_config = { + .dc_gpio_num = LCD_PIN_DC, + .wr_gpio_num = LCD_PIN_WR, + .clk_src = LCD_CLK_SRC_DEFAULT, + .data_gpio_nums = { + LCD_PIN_D0, + LCD_PIN_D1, + LCD_PIN_D2, + LCD_PIN_D3, + LCD_PIN_D4, + LCD_PIN_D5, + LCD_PIN_D6, + LCD_PIN_D7, + }, + .bus_width = 8, + .max_transfer_bytes = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t), + .psram_trans_align = 64, + .sram_trans_align = 4, + }; + ESP_ERROR_CHECK(esp_lcd_new_i80_bus(&bus_config, &i80_bus)); + + esp_lcd_panel_io_i80_config_t io_config = { + .cs_gpio_num = LCD_PIN_CS, + .pclk_hz = (20 * 1000 * 1000), + .trans_queue_depth = 7, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .dc_levels = { + .dc_idle_level = 1, + .dc_cmd_level = 0, + .dc_dummy_level = 0, + .dc_data_level = 1, + }, + .flags = { + .cs_active_high = 0, + .pclk_active_neg = 0, + .pclk_idle_low = 0, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i80(i80_bus, &io_config, &panel_io)); + + esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = LCD_PIN_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_set_gap(panel, 0, 0); + esp_lcd_panel_io_tx_param(panel_io, 0xCF, (uint8_t[]) {0x00,0x83,0x30}, 3); + esp_lcd_panel_io_tx_param(panel_io, 0xED, (uint8_t[]) {0x64,0x03,0x12,0x81}, 4); + esp_lcd_panel_io_tx_param(panel_io, 0xE8, (uint8_t[]) {0x85,0x01,0x79}, 3); + esp_lcd_panel_io_tx_param(panel_io, 0xCB, (uint8_t[]) {0x39,0x2C,0x00,0x34,0x02}, 5); + esp_lcd_panel_io_tx_param(panel_io, 0xF7, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xEA, (uint8_t[]) {0x00,0x00}, 2); + esp_lcd_panel_io_tx_param(panel_io, 0xbb, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xc3, (uint8_t[]) {0x00}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC4, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC5, (uint8_t[]) {0x20}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC6, (uint8_t[]) {0x10}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xC7, (uint8_t[]) {0xB0}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x36, (uint8_t[]) {0x60}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x3A, (uint8_t[]) {0x55}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xB1, (uint8_t[]) {0x00,0x1B}, 2); + esp_lcd_panel_io_tx_param(panel_io, 0xF2, (uint8_t[]) {0x08}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0x26, (uint8_t[]) {0x01}, 1); + esp_lcd_panel_io_tx_param(panel_io, 0xE0, (uint8_t[]) {0xD0,0x00,0x02,0x07,0x0A,0x28,0x32,0x44,0x42,0x06,0x0E,0x12,0x14,0x17}, 14); + esp_lcd_panel_io_tx_param(panel_io, 0xE1, (uint8_t[]) {0xD0,0x00,0x02,0x07,0x0A,0x28,0x31,0x54,0x47,0x0E,0x1C,0x17,0x1B,0x1E}, 14); + esp_lcd_panel_io_tx_param(panel_io, 0xB7, (uint8_t[]) {0x07}, 1); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + atk_dnesp32s3_box2_wifi() { + InitializeI2c(); + InitializeIoExpander(); + InitializePowerSaveTimer(); + InitializePowerManager(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + InitializeBoardPowerManager(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8389AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8389_ADDR, + false); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(atk_dnesp32s3_box2_wifi); + +// 定义静态成员变量 +atk_dnesp32s3_box2_wifi* atk_dnesp32s3_box2_wifi::instance_ = nullptr; diff --git a/main/boards/atk-dnesp32s3-box2-wifi/config.h b/main/boards/atk-dnesp32s3-box2-wifi/config.h new file mode 100644 index 0000000..a12384c --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-wifi/config.h @@ -0,0 +1,71 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +enum PowerSupply { + kDeviceTypecSupply, + kDeviceBatterySupply, +}; + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_42 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_41 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_48 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_47 +#define AUDIO_CODEC_ES8389_ADDR ES8389_CODEC_DEFAULT_ADDR + +#define R_BUTTON_GPIO GPIO_NUM_0 + +#define XL9555_INT_GPIO GPIO_NUM_2 +#define XIO_IO_SBU2 (IO_EXPANDER_PIN_NUM_3) +#define XIO_IO_SBU1 (IO_EXPANDER_PIN_NUM_4) +#define XIO_KEY_L (IO_EXPANDER_PIN_NUM_5) +#define XIO_KEY_Q (IO_EXPANDER_PIN_NUM_6) +#define XIO_KEY_M (IO_EXPANDER_PIN_NUM_7) +#define XIO_USB_SEL (IO_EXPANDER_PIN_NUM_8) +#define XIO_SPK_EN (IO_EXPANDER_PIN_NUM_9) +#define XIO_SYS_POW (IO_EXPANDER_PIN_NUM_10) +#define XIO_VBUS_EN (IO_EXPANDER_PIN_NUM_11) +#define XIO_EN_4G (IO_EXPANDER_PIN_NUM_12) +#define XIO_EN_3V3A (IO_EXPANDER_PIN_NUM_13) +#define XIO_CHG_CTRL (IO_EXPANDER_PIN_NUM_14) +#define XIO_CHRG (IO_EXPANDER_PIN_NUM_15) + +#define DRV_IO_EXP_OUTPUT_MASK 0x3F18 +#define DRV_IO_EXP_INPUT_MASK 0xC0E7 + +#define LCD_PIN_CS GPIO_NUM_14 +#define LCD_PIN_DC GPIO_NUM_12 +#define LCD_PIN_RD GPIO_NUM_10 +#define LCD_PIN_WR GPIO_NUM_11 +#define LCD_PIN_RST GPIO_NUM_NC +#define LCD_PIN_D0 GPIO_NUM_13 +#define LCD_PIN_D1 GPIO_NUM_9 +#define LCD_PIN_D2 GPIO_NUM_8 +#define LCD_PIN_D3 GPIO_NUM_7 +#define LCD_PIN_D4 GPIO_NUM_6 +#define LCD_PIN_D5 GPIO_NUM_5 +#define LCD_PIN_D6 GPIO_NUM_4 +#define LCD_PIN_D7 GPIO_NUM_3 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_21 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atk-dnesp32s3-box2-wifi/config.json b/main/boards/atk-dnesp32s3-box2-wifi/config.json new file mode 100644 index 0000000..2add471 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-wifi/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atk-dnesp32s3-box2-wifi", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/atk-dnesp32s3-box2-wifi/power_manager.h b/main/boards/atk-dnesp32s3-box2-wifi/power_manager.h new file mode 100644 index 0000000..103ce88 --- /dev/null +++ b/main/boards/atk-dnesp32s3-box2-wifi/power_manager.h @@ -0,0 +1,195 @@ +#pragma once +#include +#include +#include "esp_io_expander_tca95xx_16bit.h" +#include +#include +#include + + +class PowerManager { +private: + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + esp_io_expander_handle_t xl9555_; + uint32_t pin_val = 0; + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + esp_io_expander_get_level(xl9555_, DRV_IO_EXP_INPUT_MASK, &pin_val); + bool new_charging_status = ((uint8_t)((pin_val & XIO_CHRG) ? 1 : 0)) == 0; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + uint32_t temp_val = 0; + + esp_io_expander_set_dir(xl9555_, XIO_CHG_CTRL, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(xl9555_, XIO_CHG_CTRL, 0); + vTaskDelay(pdMS_TO_TICKS(500)); + + for(int t = 0; t < 10; t ++) { + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); + temp_val += adc_value; + } + + esp_io_expander_set_dir(xl9555_, XIO_CHG_CTRL, IO_EXPANDER_INPUT); + + adc_value = temp_val / 10; + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {2696, 0}, /* 3.48V -屏幕闪屏 */ + {2724, 20}, /* 3.53V */ + {2861, 40}, /* 3.7V */ + {3038, 60}, /* 3.90V */ + {3150, 80}, /* 4.02V */ + {3280, 100} /* 4.14V */ + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + low_voltage_ = adc_value; + + // ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + esp_timer_handle_t timer_handle_; + uint16_t low_voltage_ = 2630; + PowerManager(esp_io_expander_handle_t xl9555) : xl9555_(xl9555) { + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/atk-dnesp32s3/atk_dnesp32s3.cc b/main/boards/atk-dnesp32s3/atk_dnesp32s3.cc new file mode 100644 index 0000000..3f9ade0 --- /dev/null +++ b/main/boards/atk-dnesp32s3/atk_dnesp32s3.cc @@ -0,0 +1,225 @@ +#include "wifi_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/single_led.h" +#include "esp32_camera.h" + +#include +#include +#include +#include +#include + +#define TAG "atk_dnesp32s3" + +class XL9555 : public I2cDevice { +public: + XL9555(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(0x06, 0x03); + WriteReg(0x07, 0xF0); + } + + void SetOutputState(uint8_t bit, uint8_t level) { + uint16_t data; + int index = bit; + + if (bit < 8) { + data = ReadReg(0x02); + } else { + data = ReadReg(0x03); + index -= 8; + } + + data = (data & ~(1 << index)) | (level << index); + + if (bit < 8) { + WriteReg(0x02, data); + } else { + WriteReg(0x03, data); + } + } +}; + +class atk_dnesp32s3 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + XL9555* xl9555_; + Esp32Camera* camera_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + // Initialize XL9555 + xl9555_ = new XL9555(i2c_bus_, 0x20); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + ESP_LOGD(TAG, "Install panel IO"); + // 液晶屏控制IO初始化 + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 20 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG, + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + xl9555_->SetOutputState(8, 1); + xl9555_->SetOutputState(2, 0); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + // 初始化摄像头:ov2640; + // 根据正点原子官方示例参数 + void InitializeCamera() { + xl9555_->SetOutputState(OV_PWDN_IO, 0); // PWDN=低 (上电) + xl9555_->SetOutputState(OV_RESET_IO, 0); // 确保复位 + vTaskDelay(pdMS_TO_TICKS(50)); // 延长复位保持时间 + xl9555_->SetOutputState(OV_RESET_IO, 1); // 释放复位 + vTaskDelay(pdMS_TO_TICKS(50)); // 延长 50ms + + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAM_PIN_D0, + [1] = CAM_PIN_D1, + [2] = CAM_PIN_D2, + [3] = CAM_PIN_D3, + [4] = CAM_PIN_D4, + [5] = CAM_PIN_D5, + [6] = CAM_PIN_D6, + [7] = CAM_PIN_D7, + }, + .vsync_io = CAM_PIN_VSYNC, + .de_io = CAM_PIN_HREF, + .pclk_io = CAM_PIN_PCLK, + .xclk_io = CAM_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = CAM_PIN_SIOC, + .sda_pin = CAM_PIN_SIOD, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAM_PIN_RESET, // 实际由 XL9555 控制 + .pwdn_pin = CAM_PIN_PWDN, // 实际由 XL9555 控制 + .dvp_pin = dvp_pin_config, + .xclk_freq = 20000000, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + atk_dnesp32s3() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + InitializeCamera(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8388_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(atk_dnesp32s3); diff --git a/main/boards/atk-dnesp32s3/config.h b/main/boards/atk-dnesp32s3/config.h new file mode 100644 index 0000000..c0b72da --- /dev/null +++ b/main/boards/atk-dnesp32s3/config.h @@ -0,0 +1,64 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_3 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_9 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_46 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_10 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_41 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_42 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BUILTIN_LED_GPIO GPIO_NUM_1 + +#define LCD_SCLK_PIN GPIO_NUM_12 +#define LCD_MOSI_PIN GPIO_NUM_11 +#define LCD_MISO_PIN GPIO_NUM_13 +#define LCD_DC_PIN GPIO_NUM_40 +#define LCD_CS_PIN GPIO_NUM_21 + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +/* 相机引脚配置 */ +#define CAM_PIN_PWDN GPIO_NUM_NC +#define CAM_PIN_RESET GPIO_NUM_NC +#define CAM_PIN_VSYNC GPIO_NUM_47 +#define CAM_PIN_HREF GPIO_NUM_48 +#define CAM_PIN_PCLK GPIO_NUM_45 +#define CAM_PIN_XCLK GPIO_NUM_NC +#define CAM_PIN_SIOD GPIO_NUM_39 +#define CAM_PIN_SIOC GPIO_NUM_38 +#define CAM_PIN_D0 GPIO_NUM_4 +#define CAM_PIN_D1 GPIO_NUM_5 +#define CAM_PIN_D2 GPIO_NUM_6 +#define CAM_PIN_D3 GPIO_NUM_7 +#define CAM_PIN_D4 GPIO_NUM_15 +#define CAM_PIN_D5 GPIO_NUM_16 +#define CAM_PIN_D6 GPIO_NUM_17 +#define CAM_PIN_D7 GPIO_NUM_18 +#define OV_PWDN_IO 4 +#define OV_RESET_IO 5 + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atk-dnesp32s3/config.json b/main/boards/atk-dnesp32s3/config.json new file mode 100644 index 0000000..edbfeed --- /dev/null +++ b/main/boards/atk-dnesp32s3/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atk-dnesp32s3", + "sdkconfig_append": [ + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_240X240_25FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/atk-dnesp32s3m-4g/atk_dnesp32s3m.cc b/main/boards/atk-dnesp32s3m-4g/atk_dnesp32s3m.cc new file mode 100644 index 0000000..9f2f701 --- /dev/null +++ b/main/boards/atk-dnesp32s3m-4g/atk_dnesp32s3m.cc @@ -0,0 +1,220 @@ +#include "ml307_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/single_led.h" +#include "driver/gpio.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "atk_dnesp32s3m_4g" + +class atk_dnesp32s3m_4g : public Ml307Board { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + Button phone_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + Application::GetInstance().ToggleChatState(); + }); + + volume_up_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + //不插耳机 + phone_button_.OnPressDown([this]() { + gpio_set_level(SPK_EN_PIN, 1); + }); + + //插入耳机 + phone_button_.OnPressUp([this]() { + gpio_set_level(SPK_EN_PIN, 0); + }); + } + + void InitializeSt7735Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 60 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io); + + // 初始化液晶屏驱动芯片ST7735 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG, + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel); + + //使能功放引脚 + gpio_config_t io_conf; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << SPK_EN_PIN); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + gpio_set_level(SPK_EN_PIN, 0); + + //检测耳机是否插入,插入时为高电平 + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << PHONE_CK_PIN); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + //耳机插入 + if (gpio_get_level(PHONE_CK_PIN)) { + gpio_set_level(SPK_EN_PIN, 1); + } + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + + uint8_t data0[] = {0x02, 0x1c, 0x07, 0x12, 0x37, 0x32, 0x29, 0x2d, 0x29, 0x25, 0x2B, 0x39, 0x00, 0x01, 0x03, 0x10}; + uint8_t data1[] = {0x03, 0x1d, 0x07, 0x06, 0x2E, 0x2C, 0x29, 0x2D, 0x2E, 0x2E, 0x37, 0x3F, 0x00, 0x00, 0x02, 0x10}; + esp_lcd_panel_io_tx_param(panel_io, 0xe0, data0, 16); + esp_lcd_panel_io_tx_param(panel_io, 0xe1, data1, 16); + + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + atk_dnesp32s3m_4g() : Ml307Board(Module_4G_TX_PIN, Module_4G_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO), + phone_button_(PHONE_CK_PIN, true) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7735Display(); + InitializeButtons(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8388_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } +}; + +DECLARE_BOARD(atk_dnesp32s3m_4g); diff --git a/main/boards/atk-dnesp32s3m-4g/config.h b/main/boards/atk-dnesp32s3m-4g/config.h new file mode 100644 index 0000000..92505c5 --- /dev/null +++ b/main/boards/atk-dnesp32s3m-4g/config.h @@ -0,0 +1,53 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_48 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_47 + +#define Module_4G_RX_PIN GPIO_NUM_21 +#define Module_4G_TX_PIN GPIO_NUM_45 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_16 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_4 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_5 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BUILTIN_LED_GPIO GPIO_NUM_1 + +#define LCD_SCLK_PIN GPIO_NUM_12 +#define LCD_MOSI_PIN GPIO_NUM_11 +#define LCD_MISO_PIN GPIO_NUM_13 +#define LCD_DC_PIN GPIO_NUM_40 +#define LCD_CS_PIN GPIO_NUM_39 +#define LCD_RST_PIN GPIO_NUM_38 + +#define SPK_EN_PIN GPIO_NUM_42 +#define PHONE_CK_PIN GPIO_NUM_3 + +#define DISPLAY_WIDTH 160 +#define DISPLAY_HEIGHT 80 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 1 +#define DISPLAY_OFFSET_Y 26 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_41 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atk-dnesp32s3m-wifi/atk_dnesp32s3m.cc b/main/boards/atk-dnesp32s3m-wifi/atk_dnesp32s3m.cc new file mode 100644 index 0000000..1ae96a1 --- /dev/null +++ b/main/boards/atk-dnesp32s3m-wifi/atk_dnesp32s3m.cc @@ -0,0 +1,230 @@ +#include "wifi_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/single_led.h" +#include "driver/gpio.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "atk_dnesp32s3m_wifi" + +class atk_dnesp32s3m_wifi : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + Button phone_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + volume_up_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + //不插耳机 + phone_button_.OnPressDown([this]() { + gpio_set_level(SPK_EN_PIN, 1); + }); + + //插入耳机 + phone_button_.OnPressUp([this]() { + gpio_set_level(SPK_EN_PIN, 0); + }); + + } + + void InitializeSt7735Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 60 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + //使能功放引脚 + gpio_config_t io_conf; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << SPK_EN_PIN); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + gpio_set_level(SPK_EN_PIN, 0); + + //检测耳机是否插入,插入时为高电平 + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << PHONE_CK_PIN); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + //耳机插入 + if (gpio_get_level(PHONE_CK_PIN)) { + gpio_set_level(SPK_EN_PIN, 1); + } + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + + uint8_t data0[] = {0x02, 0x1c, 0x07, 0x12, 0x37, 0x32, 0x29, 0x2d, 0x29, 0x25, 0x2B, 0x39, 0x00, 0x01, 0x03, 0x10}; + uint8_t data1[] = {0x03, 0x1d, 0x07, 0x06, 0x2E, 0x2C, 0x29, 0x2D, 0x2E, 0x2E, 0x37, 0x3F, 0x00, 0x00, 0x02, 0x10}; + esp_lcd_panel_io_tx_param(panel_io, 0xe0, data0, 16); + esp_lcd_panel_io_tx_param(panel_io, 0xe1, data1, 16); + + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + atk_dnesp32s3m_wifi() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO), + phone_button_(PHONE_CK_PIN, true) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7735Display(); + InitializeButtons(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8388_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } +}; + +DECLARE_BOARD(atk_dnesp32s3m_wifi); diff --git a/main/boards/atk-dnesp32s3m-wifi/config.h b/main/boards/atk-dnesp32s3m-wifi/config.h new file mode 100644 index 0000000..df22181 --- /dev/null +++ b/main/boards/atk-dnesp32s3m-wifi/config.h @@ -0,0 +1,52 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_48 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_47 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_16 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_4 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_5 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BUILTIN_LED_GPIO GPIO_NUM_1 + +#define LCD_SCLK_PIN GPIO_NUM_12 +#define LCD_MOSI_PIN GPIO_NUM_11 +#define LCD_MISO_PIN GPIO_NUM_13 +#define LCD_DC_PIN GPIO_NUM_40 +#define LCD_CS_PIN GPIO_NUM_39 +#define LCD_RST_PIN GPIO_NUM_38 + +#define SPK_EN_PIN GPIO_NUM_42 +#define PHONE_CK_PIN GPIO_NUM_3 + +#define DISPLAY_WIDTH 160 +#define DISPLAY_HEIGHT 80 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 1 +#define DISPLAY_OFFSET_Y 26 +// #define DISPLAY_OFFSET_X 0 +// #define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_41 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/atom-echos3r/README.md b/main/boards/atom-echos3r/README.md new file mode 100644 index 0000000..ccb452f --- /dev/null +++ b/main/boards/atom-echos3r/README.md @@ -0,0 +1,45 @@ +# AtomEchoS3R +## 简介 + +AtomEchoS3R 是 M5Stack 推出的基于 ESP32-S3-PICO-1-N8R8 的物联网可编程控制器,采用了 ES8311 单声道音频解码器、MEMS 麦克风和 NS4150B 功率放大器的集成方案。 + +开发版**不带屏幕、不带额外按键**,需要使用语音唤醒。必要时,需要使用 `idf.py monitor` 查看 log 以确定运行状态。 + +## 配置、编译命令 + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig 并配置** + +```bash +idf.py menuconfig +``` + +分别配置如下选项: + +- `Xiaozhi Assistant` → `Board Type` → 选择 `AtomEchoS3R` +- `Partition Table` → `Custom partition CSV file` → 删除原有内容,输入 `partitions/v2/8m.csv` +- `Serial flasher config` → `Flash size` → 选择 `8 MB` +- `Component config` → `ESP PSRAM` → `Support for external, SPI-connected RAM` → `SPI RAM config` → 选择 `Octal Mode PSRAM` + +按 `S` 保存,按 `Q` 退出。 + +**编译** + +```bash +idf.py build +``` + +**烧录** + +将 AtomEchoS3R 连接到电脑,按住侧面 RESET 按键,直到 RESET 按键下方绿灯闪烁。 + +```bash +idf.py flash +``` + +烧录完毕后,按一下 RESET 按钮重启设备。 diff --git a/main/boards/atom-echos3r/atom_echos3r.cc b/main/boards/atom-echos3r/atom_echos3r.cc new file mode 100644 index 0000000..bb9c8e4 --- /dev/null +++ b/main/boards/atom-echos3r/atom_echos3r.cc @@ -0,0 +1,91 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "assets/lang_config.h" + +#include +#include +#include + +#define TAG "AtomEchoS3R" + +class AtomEchoS3rBaseBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } +public: + AtomEchoS3rBaseBoard() : boot_button_(USER_BUTTON_GPIO) { + InitializeI2c(); + I2cDetect(); + InitializeButtons(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_GPIO_PA, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } +}; + +DECLARE_BOARD(AtomEchoS3rBaseBoard); diff --git a/main/boards/atom-echos3r/config.h b/main/boards/atom-echos3r/config.h new file mode 100644 index 0000000..4803c42 --- /dev/null +++ b/main/boards/atom-echos3r/config.h @@ -0,0 +1,29 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// AtomEchoS3R Board configuration + +#include + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_11 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_3 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_4 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_48 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_45 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_0 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_GPIO_PA GPIO_NUM_18 + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define USER_BUTTON_GPIO GPIO_NUM_41 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/atom-echos3r/config.json b/main/boards/atom-echos3r/config.json new file mode 100644 index 0000000..7e7328d --- /dev/null +++ b/main/boards/atom-echos3r/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atom-echos3r", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"" + ] + } + ] +} diff --git a/main/boards/atommatrix-echo-base/README.md b/main/boards/atommatrix-echo-base/README.md new file mode 100644 index 0000000..67ab32f --- /dev/null +++ b/main/boards/atommatrix-echo-base/README.md @@ -0,0 +1,25 @@ +# 编译配置命令 + +**配置编译目标为 ESP32:** + +```bash +idf.py set-target esp32 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> AtomMatrix + Echo Base +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/atommatrix-echo-base/atommatrix_echo_base.cc b/main/boards/atommatrix-echo-base/atommatrix_echo_base.cc new file mode 100644 index 0000000..5bfd3cc --- /dev/null +++ b/main/boards/atommatrix-echo-base/atommatrix_echo_base.cc @@ -0,0 +1,133 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" + +#include +#include +#include +#include "led/circular_strip.h" + +#define TAG "XX+EchoBase" + +#define PI4IOE_ADDR 0x43 +#define PI4IOE_REG_CTRL 0x00 +#define PI4IOE_REG_IO_PP 0x07 +#define PI4IOE_REG_IO_DIR 0x03 +#define PI4IOE_REG_IO_OUT 0x05 +#define PI4IOE_REG_IO_PULLUP 0x0D + +class Pi4ioe : public I2cDevice { +public: + Pi4ioe(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(PI4IOE_REG_IO_PP, 0x00); // Set to high-impedance + WriteReg(PI4IOE_REG_IO_PULLUP, 0xFF); // Enable pull-up + WriteReg(PI4IOE_REG_IO_DIR, 0x6E); // Set input=0, output=1 + WriteReg(PI4IOE_REG_IO_OUT, 0xFF); // Set outputs to 1 + } + + void SetSpeakerMute(bool mute) { + WriteReg(PI4IOE_REG_IO_OUT, mute ? 0x00 : 0xFF); + } +}; + +class AtomMatrixEchoBaseBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + + Pi4ioe* pi4ioe_; + + Button face_button_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + void InitializePi4ioe() { + ESP_LOGI(TAG, "Init PI4IOE"); + pi4ioe_ = new Pi4ioe(i2c_bus_, PI4IOE_ADDR); + pi4ioe_->SetSpeakerMute(false); + } + + void InitializeButtons() { + face_button_.OnClick([this]() { + + ESP_LOGI(TAG, " ===>>> face_button_.OnClick "); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + AtomMatrixEchoBaseBoard() : face_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + I2cDetect(); + InitializePi4ioe(); + InitializeButtons(); + } + + virtual Led* GetLed() override { + static CircularStrip led(BUILTIN_LED_GPIO, 25); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_1, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_GPIO_PA, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } + +}; + +DECLARE_BOARD(AtomMatrixEchoBaseBoard); diff --git a/main/boards/atommatrix-echo-base/config.h b/main/boards/atommatrix-echo-base/config.h new file mode 100644 index 0000000..d1684cb --- /dev/null +++ b/main/boards/atommatrix-echo-base/config.h @@ -0,0 +1,29 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// AtomMatrix+EchoBase Board configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_19 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_33 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_23 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_22 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_25 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_21 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_GPIO_PA GPIO_NUM_NC + +#define BUILTIN_LED_GPIO GPIO_NUM_27 +#define BOOT_BUTTON_GPIO GPIO_NUM_39 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/atommatrix-echo-base/config.json b/main/boards/atommatrix-echo-base/config.json new file mode 100644 index 0000000..794d574 --- /dev/null +++ b/main/boards/atommatrix-echo-base/config.json @@ -0,0 +1,10 @@ +{ + "target": "esp32", + "builds": [ + { + "name": "atommatrix-echo-base", + "sdkconfig_append": [ + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/atoms3-echo-base/README.md b/main/boards/atoms3-echo-base/README.md new file mode 100644 index 0000000..ef2ad28 --- /dev/null +++ b/main/boards/atoms3-echo-base/README.md @@ -0,0 +1,49 @@ +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> AtomS3 + Echo Base +``` + +**关闭语音唤醒:** + +``` +Xiaozhi Assistant -> [ ] 启用语音唤醒与音频处理 -> Unselect +``` + +**修改 flash 大小:** + +``` +Serial flasher config -> Flash size -> 8 MB +``` + +**修改分区表:** + +``` +Partition Table -> Custom partition CSV file -> partitions/v2/8m.csv +``` + +**关闭片外 PSRAM:** + +``` +Component config -> ESP PSRAM -> [ ] Support for external, SPI-connected RAM -> Unselect +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/atoms3-echo-base/atoms3_echo_base.cc b/main/boards/atoms3-echo-base/atoms3_echo_base.cc new file mode 100644 index 0000000..64e592e --- /dev/null +++ b/main/boards/atoms3-echo-base/atoms3_echo_base.cc @@ -0,0 +1,228 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "AtomS3+EchoBase" + +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb2, (uint8_t[]){0x2f}, 1, 0}, + {0xb3, (uint8_t[]){0x03}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x01}, 1, 0}, + {0xac, (uint8_t[]){0xcb}, 1, 0}, + {0xab, (uint8_t[]){0x0e}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x19}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xe8, (uint8_t[]){0x24}, 1, 0}, + {0xe9, (uint8_t[]){0x48}, 1, 0}, + {0xea, (uint8_t[]){0x22}, 1, 0}, + {0xc6, (uint8_t[]){0x30}, 1, 0}, + {0xc7, (uint8_t[]){0x18}, 1, 0}, + {0xf0, + (uint8_t[]){0x1f, 0x28, 0x04, 0x3e, 0x2a, 0x2e, 0x20, 0x00, 0x0c, 0x06, + 0x00, 0x1c, 0x1f, 0x0f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x00, 0x2d, 0x2f, 0x3c, 0x6f, 0x1c, 0x0b, 0x00, 0x00, 0x00, + 0x07, 0x0d, 0x11, 0x0f}, + 14, 0}, +}; + +class AtomS3EchoBaseBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Display* display_; + Button boot_button_; + bool is_echo_base_connected_ = false; + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + is_echo_base_connected_ = false; + uint8_t echo_base_connected_flag = 0x00; + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + if (address == 0x18) { + echo_base_connected_flag |= 0xF0; + } else if (address == 0x43) { + echo_base_connected_flag |= 0x0F; + } + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + is_echo_base_connected_ = (echo_base_connected_flag == 0xFF); + } + + void CheckEchoBaseConnection() { + if (is_echo_base_connected_) { + return; + } + + // Pop error page + InitializeSpi(); + InitializeGc9107Display(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + display_->SetStatus(Lang::Strings::ERROR); + display_->SetEmotion("triangle_exclamation"); + display_->SetChatMessage("system", "Echo Base\nnot connected"); + + while (1) { + ESP_LOGE(TAG, "Atomic Echo Base is disconnected"); + vTaskDelay(pdMS_TO_TICKS(1000)); + + // Rerun detection + I2cDetect(); + if (is_echo_base_connected_) { + vTaskDelay(pdMS_TO_TICKS(500)); + I2cDetect(); + if (is_echo_base_connected_) { + ESP_LOGI(TAG, "Atomic Echo Base is reconnected"); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_restart(); + } + } + } + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_21; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_17; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeGc9107Display() { + ESP_LOGI(TAG, "Init GC9107 display"); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_15; + io_config.dc_gpio_num = GPIO_NUM_33; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_34; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; + panel_config.bits_per_pixel = 16; // Implemented by LCD command `3Ah` (16/18) + panel_config.vendor_config = &gc9107_vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + display_ = new SpiLcdDisplay(io_handle, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + AtomS3EchoBaseBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + I2cDetect(); + CheckEchoBaseConnection(); + InitializeSpi(); + InitializeGc9107Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_1, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_GPIO_PA, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT, 256); + return &backlight; + } +}; + +DECLARE_BOARD(AtomS3EchoBaseBoard); \ No newline at end of file diff --git a/main/boards/atoms3-echo-base/config.h b/main/boards/atoms3-echo-base/config.h new file mode 100644 index 0000000..6b2fdad --- /dev/null +++ b/main/boards/atoms3-echo-base/config.h @@ -0,0 +1,43 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// AtomS3+EchoBase Board configuration + +#include + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_6 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_5 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_38 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_39 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_GPIO_PA GPIO_NUM_NC + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_41 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 32 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_16 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ \ No newline at end of file diff --git a/main/boards/atoms3-echo-base/config.json b/main/boards/atoms3-echo-base/config.json new file mode 100644 index 0000000..cd2fd6e --- /dev/null +++ b/main/boards/atoms3-echo-base/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atoms3-echo-base", + "sdkconfig_append": [ + "CONFIG_SPIRAM=n", + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/atoms3r-cam-m12-echo-base/README.md b/main/boards/atoms3r-cam-m12-echo-base/README.md new file mode 100644 index 0000000..83738ec --- /dev/null +++ b/main/boards/atoms3r-cam-m12-echo-base/README.md @@ -0,0 +1,60 @@ +# AtomS3R CAM/M12 + Echo Base + +## 简介 + + + +AtomS3R CAM、AtomS3R M12 是 M5Stack 推出的基于 ESP32-S3-PICO-1-N8R8 的物联网可编程控制器,搭载了摄像头。Atomic Echo Base 是一款专为 M5 Atom 系列主机设计的语音识别底座,采用了 ES8311 单声道音频解码器、MEMS 麦克风和 NS4150B 功率放大器的集成方案。 + +两款开发版均**不带屏幕、不带额外按键**,需要使用语音唤醒。必要时,需要使用 `idf.py monitor` 查看 log 以确定运行状态。 + +> ![NOTE] +> +> 自版本 [待定] 起,由于依赖库不支持 OV3660 传感器,AtomS3R M12 无法使用摄像头识别功能。 +> +> AtomS3R CAM 不受影响;使用旧版本小智固件的 AtomS3R M12 不受影响。 + +## 配置、编译命令 + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig 并配置** + +```bash +idf.py menuconfig +``` + +分别配置如下选项: + +- `Xiaozhi Assistant` → `Board Type` → 选择 `AtomS3R CAM/M12 + Echo Base` +- `Xiaozhi Assistant` → `IoT Protocol` → 选择 `MCP协议` 可开启摄像头识别功能 +- `Partition Table` → `Custom partition CSV file` → 删除原有内容,输入 `partitions/v2/8m.csv` +- `Serial flasher config` → `Flash size` → 选择 `8 MB` + +按 `S` 保存,按 `Q` 退出。 + +**编译** + +```bash +idf.py build +``` + +**烧录** + +将 AtomS3R CAM/M12 连接到电脑,按住侧面 RESET 按键,直到 RESET 按键下方绿灯闪烁。 + +```bash +idf.py flash +``` + +烧录完毕后,按一下 RESET 按钮重启。 diff --git a/main/boards/atoms3r-cam-m12-echo-base/atoms3r_cam_m12_echo_base.cc b/main/boards/atoms3r-cam-m12-echo-base/atoms3r_cam_m12_echo_base.cc new file mode 100644 index 0000000..b74f0f0 --- /dev/null +++ b/main/boards/atoms3r-cam-m12-echo-base/atoms3r_cam_m12_echo_base.cc @@ -0,0 +1,205 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include "esp32_camera.h" + +#define TAG "AtomS3R CAM/M12 + EchoBase" + +#define PI4IOE_ADDR 0x43 +#define PI4IOE_REG_CTRL 0x00 +#define PI4IOE_REG_IO_PP 0x07 +#define PI4IOE_REG_IO_DIR 0x03 +#define PI4IOE_REG_IO_OUT 0x05 +#define PI4IOE_REG_IO_PULLUP 0x0D + +class Pi4ioe : public I2cDevice { +public: + Pi4ioe(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(PI4IOE_REG_IO_PP, 0x00); // Set to high-impedance + WriteReg(PI4IOE_REG_IO_PULLUP, 0xFF); // Enable pull-up + WriteReg(PI4IOE_REG_IO_DIR, 0x6E); // Set input=0, output=1 + WriteReg(PI4IOE_REG_IO_OUT, 0xFF); // Set outputs to 1 + } + + void SetSpeakerMute(bool mute) { + WriteReg(PI4IOE_REG_IO_OUT, mute ? 0x00 : 0xFF); + } +}; + +class AtomS3rCamM12EchoBaseBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pi4ioe* pi4ioe_ = nullptr; + bool is_echo_base_connected_ = false; + Esp32Camera* camera_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + is_echo_base_connected_ = false; + uint8_t echo_base_connected_flag = 0x00; + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + if (address == 0x18) { + echo_base_connected_flag |= 0xF0; + } else if (address == 0x43) { + echo_base_connected_flag |= 0x0F; + } + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + is_echo_base_connected_ = (echo_base_connected_flag == 0xFF); + } + + void CheckEchoBaseConnection() { + if (is_echo_base_connected_) { + return; + } + + while (1) { + ESP_LOGE(TAG, "Atomic Echo Base is disconnected"); + vTaskDelay(pdMS_TO_TICKS(1000)); + + // Rerun detection + I2cDetect(); + if (is_echo_base_connected_) { + vTaskDelay(pdMS_TO_TICKS(500)); + I2cDetect(); + if (is_echo_base_connected_) { + ESP_LOGI(TAG, "Atomic Echo Base is reconnected"); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_restart(); + } + } + } + } + + void InitializePi4ioe() { + ESP_LOGI(TAG, "Init PI4IOE"); + pi4ioe_ = new Pi4ioe(i2c_bus_, PI4IOE_ADDR); + pi4ioe_->SetSpeakerMute(false); + } + + void EnableCameraPower() { + gpio_reset_pin((gpio_num_t)18); + gpio_set_direction((gpio_num_t)18, GPIO_MODE_OUTPUT); + gpio_set_pull_mode((gpio_num_t)18, GPIO_PULLDOWN_ONLY); + + ESP_LOGI(TAG, "Camera Power Enabled"); + + vTaskDelay(pdMS_TO_TICKS(1000)); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = CAMERA_PIN_SIOC, + .sda_pin = CAMERA_PIN_SIOD, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + camera_->SetHMirror(false); + } + + virtual Camera* GetCamera() override { + return camera_; + } +public: + AtomS3rCamM12EchoBaseBoard() { + EnableCameraPower(); // IO18 还会控制指示灯 + InitializeCamera(); + InitializeI2c(); + I2cDetect(); + CheckEchoBaseConnection(); + InitializePi4ioe(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_GPIO_PA, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } +}; + +DECLARE_BOARD(AtomS3rCamM12EchoBaseBoard); diff --git a/main/boards/atoms3r-cam-m12-echo-base/config.h b/main/boards/atoms3r-cam-m12-echo-base/config.h new file mode 100644 index 0000000..61fef49 --- /dev/null +++ b/main/boards/atoms3r-cam-m12-echo-base/config.h @@ -0,0 +1,49 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// AtomS3R M12+EchoBase Board configuration + +#include + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_6 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_5 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_38 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_39 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_GPIO_PA GPIO_NUM_NC + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_41 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + + +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_VSYNC GPIO_NUM_10 +#define CAMERA_PIN_HREF GPIO_NUM_14 +#define CAMERA_PIN_PCLK GPIO_NUM_40 +#define CAMERA_PIN_XCLK GPIO_NUM_21 +#define CAMERA_PIN_SIOD GPIO_NUM_12 +#define CAMERA_PIN_SIOC GPIO_NUM_9 +#define CAMERA_PIN_D0 GPIO_NUM_3 +#define CAMERA_PIN_D1 GPIO_NUM_42 +#define CAMERA_PIN_D2 GPIO_NUM_46 +#define CAMERA_PIN_D3 GPIO_NUM_48 +#define CAMERA_PIN_D4 GPIO_NUM_4 +#define CAMERA_PIN_D5 GPIO_NUM_17 +#define CAMERA_PIN_D6 GPIO_NUM_11 +#define CAMERA_PIN_D7 GPIO_NUM_13 +#define CAMERA_XCLK_FREQ (20000000) +#define XCLK_FREQ_HZ CAMERA_XCLK_FREQ + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/atoms3r-cam-m12-echo-base/config.json b/main/boards/atoms3r-cam-m12-echo-base/config.json new file mode 100644 index 0000000..1c79813 --- /dev/null +++ b/main/boards/atoms3r-cam-m12-echo-base/config.json @@ -0,0 +1,15 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atoms3r-cam-m12-echo-base", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_CAMERA_GC0308=y", + "CONFIG_CAMERA_GC0308_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_GC0308_DVP_YUV422_320X240_20FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/atoms3r-echo-base/README.md b/main/boards/atoms3r-echo-base/README.md new file mode 100644 index 0000000..13e8a36 --- /dev/null +++ b/main/boards/atoms3r-echo-base/README.md @@ -0,0 +1,43 @@ +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> AtomS3R + Echo Base +``` + +**修改 flash 大小:** + +``` +Serial flasher config -> Flash size -> 8 MB +``` + +**修改分区表:** + +``` +Partition Table -> Custom partition CSV file -> partitions/v2/8m.csv +``` + +**修改 psram 配置:** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> Octal Mode PSRAM +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/atoms3r-echo-base/atoms3r_echo_base.cc b/main/boards/atoms3r-echo-base/atoms3r_echo_base.cc new file mode 100644 index 0000000..3407828 --- /dev/null +++ b/main/boards/atoms3r-echo-base/atoms3r_echo_base.cc @@ -0,0 +1,308 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "AtomS3R+EchoBase" + +#define PI4IOE_ADDR 0x43 +#define PI4IOE_REG_CTRL 0x00 +#define PI4IOE_REG_IO_PP 0x07 +#define PI4IOE_REG_IO_DIR 0x03 +#define PI4IOE_REG_IO_OUT 0x05 +#define PI4IOE_REG_IO_PULLUP 0x0D + +class Pi4ioe : public I2cDevice { +public: + Pi4ioe(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(PI4IOE_REG_IO_PP, 0x00); // Set to high-impedance + WriteReg(PI4IOE_REG_IO_PULLUP, 0xFF); // Enable pull-up + WriteReg(PI4IOE_REG_IO_DIR, 0x6E); // Set input=0, output=1 + WriteReg(PI4IOE_REG_IO_OUT, 0xFF); // Set outputs to 1 + } + + void SetSpeakerMute(bool mute) { + WriteReg(PI4IOE_REG_IO_OUT, mute ? 0x00 : 0xFF); + } +}; + +class Lp5562 : public I2cDevice { +public: + Lp5562(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(0x00, 0B01000000); // Set chip_en to 1 + WriteReg(0x08, 0B00000001); // Enable internal clock + WriteReg(0x70, 0B00000000); // Configure all LED outputs to be controlled from I2C registers + + // PWM clock frequency 558 Hz + auto data = ReadReg(0x08); + data = data | 0B01000000; + WriteReg(0x08, data); + } + + void SetBrightness(uint8_t brightness) { + // Map 0~100 to 0~255 + brightness = brightness * 255 / 100; + WriteReg(0x0E, brightness); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(Lp5562* lp5562) : lp5562_(lp5562) {} + + void SetBrightnessImpl(uint8_t brightness) override { + if (lp5562_) { + lp5562_->SetBrightness(brightness); + } else { + ESP_LOGE(TAG, "LP5562 not available"); + } + } + +private: + Lp5562* lp5562_ = nullptr; +}; + +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb2, (uint8_t[]){0x2f}, 1, 0}, + {0xb3, (uint8_t[]){0x03}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x01}, 1, 0}, + {0xac, (uint8_t[]){0xcb}, 1, 0}, + {0xab, (uint8_t[]){0x0e}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x19}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xe8, (uint8_t[]){0x24}, 1, 0}, + {0xe9, (uint8_t[]){0x48}, 1, 0}, + {0xea, (uint8_t[]){0x22}, 1, 0}, + {0xc6, (uint8_t[]){0x30}, 1, 0}, + {0xc7, (uint8_t[]){0x18}, 1, 0}, + {0xf0, + (uint8_t[]){0x1f, 0x28, 0x04, 0x3e, 0x2a, 0x2e, 0x20, 0x00, 0x0c, 0x06, + 0x00, 0x1c, 0x1f, 0x0f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x00, 0x2d, 0x2f, 0x3c, 0x6f, 0x1c, 0x0b, 0x00, 0x00, 0x00, + 0x07, 0x0d, 0x11, 0x0f}, + 14, 0}, +}; + +class AtomS3rEchoBaseBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + i2c_master_bus_handle_t i2c_bus_internal_; + Pi4ioe* pi4ioe_ = nullptr; + Lp5562* lp5562_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + bool is_echo_base_connected_ = false; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + i2c_bus_cfg.i2c_port = I2C_NUM_0; + i2c_bus_cfg.sda_io_num = GPIO_NUM_45; + i2c_bus_cfg.scl_io_num = GPIO_NUM_0; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_internal_)); + } + + void I2cDetect() { + is_echo_base_connected_ = false; + uint8_t echo_base_connected_flag = 0x00; + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + if (address == 0x18) { + echo_base_connected_flag |= 0xF0; + } else if (address == 0x43) { + echo_base_connected_flag |= 0x0F; + } + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + is_echo_base_connected_ = (echo_base_connected_flag == 0xFF); + } + + void CheckEchoBaseConnection() { + if (is_echo_base_connected_) { + return; + } + + // Pop error page + InitializeLp5562(); + InitializeSpi(); + InitializeGc9107Display(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + display_->SetStatus(Lang::Strings::ERROR); + display_->SetEmotion("triangle_exclamation"); + display_->SetChatMessage("system", "Echo Base\nnot connected"); + + while (1) { + ESP_LOGE(TAG, "Atomic Echo Base is disconnected"); + vTaskDelay(pdMS_TO_TICKS(1000)); + + // Rerun detection + I2cDetect(); + if (is_echo_base_connected_) { + vTaskDelay(pdMS_TO_TICKS(500)); + I2cDetect(); + if (is_echo_base_connected_) { + ESP_LOGI(TAG, "Atomic Echo Base is reconnected"); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_restart(); + } + } + } + } + + void InitializePi4ioe() { + ESP_LOGI(TAG, "Init PI4IOE"); + pi4ioe_ = new Pi4ioe(i2c_bus_, PI4IOE_ADDR); + pi4ioe_->SetSpeakerMute(false); + } + + void InitializeLp5562() { + ESP_LOGI(TAG, "Init LP5562"); + lp5562_ = new Lp5562(i2c_bus_internal_, 0x30); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_21; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_15; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeGc9107Display() { + ESP_LOGI(TAG, "Init GC9107 display"); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_14; + io_config.dc_gpio_num = GPIO_NUM_42; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_48; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; + panel_config.bits_per_pixel = 16; // Implemented by LCD command `3Ah` (16/18) + panel_config.vendor_config = &gc9107_vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + display_ = new SpiLcdDisplay(io_handle, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + AtomS3rEchoBaseBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + I2cDetect(); + CheckEchoBaseConnection(); + InitializePi4ioe(); + InitializeLp5562(); + InitializeSpi(); + InitializeGc9107Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_1, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_GPIO_PA, + AUDIO_CODEC_ES8311_ADDR, + false); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight *GetBacklight() override { + static CustomBacklight backlight(lp5562_); + return &backlight; + } +}; + +DECLARE_BOARD(AtomS3rEchoBaseBoard); diff --git a/main/boards/atoms3r-echo-base/config.h b/main/boards/atoms3r-echo-base/config.h new file mode 100644 index 0000000..d519c2e --- /dev/null +++ b/main/boards/atoms3r-echo-base/config.h @@ -0,0 +1,43 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// AtomS3R+EchoBase Board configuration + +#include + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_6 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_5 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_38 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_39 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_GPIO_PA GPIO_NUM_NC + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_41 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 32 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/atoms3r-echo-base/config.json b/main/boards/atoms3r-echo-base/config.json new file mode 100644 index 0000000..d3b1549 --- /dev/null +++ b/main/boards/atoms3r-echo-base/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "atoms3r-echo-base", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/bread-compact-esp32-lcd/config.h b/main/boards/bread-compact-esp32-lcd/config.h new file mode 100644 index 0000000..d9a2148 --- /dev/null +++ b/main/boards/bread-compact-esp32-lcd/config.h @@ -0,0 +1,278 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_25 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_26 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_32 + +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_33 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_27 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_5 +#define ASR_BUTTON_GPIO GPIO_NUM_19 +#define BUILTIN_LED_GPIO GPIO_NUM_2 + +#define ML307_RX_PIN GPIO_NUM_16 +#define ML307_TX_PIN GPIO_NUM_17 + +#ifdef CONFIG_LCD_ST7789_240X240_7PIN +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_22 +#define DISPLAY_CS_PIN GPIO_NUM_NC +#else +#define DISPLAY_CS_PIN GPIO_NUM_22 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_23 +#endif + +#define DISPLAY_MOSI_PIN GPIO_NUM_4 +#define DISPLAY_CLK_PIN GPIO_NUM_15 +#define DISPLAY_DC_PIN GPIO_NUM_21 +#define DISPLAY_RST_PIN GPIO_NUM_18 + + +#ifdef CONFIG_LCD_ST7789_240X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X320_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_170X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 170 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 35 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_172X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 172 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 34 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X280 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240_7PIN +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 2 +#endif + +#ifdef CONFIG_LCD_ST7789_240X135 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 135 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 40 +#define DISPLAY_OFFSET_Y 53 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X160 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X128 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 32 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320 +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320_NO_IPS +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_GC9A01_240X240 +#define LCD_TYPE_GC9A01_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_CUSTOM +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-esp32-lcd/config.json b/main/boards/bread-compact-esp32-lcd/config.json new file mode 100644 index 0000000..07a853a --- /dev/null +++ b/main/boards/bread-compact-esp32-lcd/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32", + "builds": [ + { + "name": "bread-compact-esp32-lcd", + "sdkconfig_append": [ + "LCD_ST7789_240X240_7PIN=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/bread-compact-esp32-lcd/esp32_bread_board_lcd.cc b/main/boards/bread-compact-esp32-lcd/esp32_bread_board_lcd.cc new file mode 100644 index 0000000..5574786 --- /dev/null +++ b/main/boards/bread-compact-esp32-lcd/esp32_bread_board_lcd.cc @@ -0,0 +1,213 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include +#include +#include + +#if defined(LCD_TYPE_ILI9341_SERIAL) +#include "esp_lcd_ili9341.h" +#endif + +#if defined(LCD_TYPE_GC9A01_SERIAL) +#include "esp_lcd_gc9a01.h" +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; +#endif + +#define TAG "ESP32-LCD-MarsbearSupport" + +class CompactWifiBoardLCD : public DualNetworkBoard { +private: + Button boot_button_; + Button touch_button_; + Button asr_button_; + + LcdDisplay* display_; + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; +#if defined(LCD_TYPE_ILI9341_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); +#elif defined(LCD_TYPE_GC9A01_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel)); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; +#else + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); +#endif + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); +#ifdef LCD_TYPE_GC9A01_SERIAL + panel_config.vendor_config = &gc9107_vendor_config; +#endif + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + + // 配置 GPIO + gpio_config_t io_conf = { + .pin_bit_mask = 1ULL << BUILTIN_LED_GPIO, // 设置需要配置的 GPIO 引脚 + .mode = GPIO_MODE_OUTPUT, // 设置为输出模式 + .pull_up_en = GPIO_PULLUP_DISABLE, // 禁用上拉 + .pull_down_en = GPIO_PULLDOWN_DISABLE, // 禁用下拉 + .intr_type = GPIO_INTR_DISABLE // 禁用中断 + }; + gpio_config(&io_conf); // 应用配置 + + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + gpio_set_level(BUILTIN_LED_GPIO, 1); + app.ToggleChatState(); + }); + + + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + asr_button_.OnClick([this]() { + std::string wake_word="你好小智"; + Application::GetInstance().WakeWordInvoke(wake_word); + }); + + touch_button_.OnPressDown([this]() { + gpio_set_level(BUILTIN_LED_GPIO, 1); + Application::GetInstance().StartListening(); + }); + + touch_button_.OnPressUp([this]() { + gpio_set_level(BUILTIN_LED_GPIO, 0); + Application::GetInstance().StopListening(); + }); + + } + +public: + CompactWifiBoardLCD() : + DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), touch_button_(TOUCH_BUTTON_GPIO), asr_button_(ASR_BUTTON_GPIO) { + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } +}; + +DECLARE_BOARD(CompactWifiBoardLCD); diff --git a/main/boards/bread-compact-esp32/README.md b/main/boards/bread-compact-esp32/README.md new file mode 100644 index 0000000..617e83b --- /dev/null +++ b/main/boards/bread-compact-esp32/README.md @@ -0,0 +1,25 @@ +# 编译配置命令 + +**配置编译目标为 ESP32:** + +```bash +idf.py set-target esp32 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> 面包板 ESP32 DevKit +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/bread-compact-esp32/config.h b/main/boards/bread-compact-esp32/config.h new file mode 100644 index 0000000..0d5ab75 --- /dev/null +++ b/main/boards/bread-compact-esp32/config.h @@ -0,0 +1,58 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_25 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_26 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_32 + +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_33 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_27 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_5 +#define ASR_BUTTON_GPIO GPIO_NUM_19 +#define BUILTIN_LED_GPIO GPIO_NUM_2 + +#define ML307_RX_PIN GPIO_NUM_16 +#define ML307_TX_PIN GPIO_NUM_17 + +#define DISPLAY_SDA_PIN GPIO_NUM_4 +#define DISPLAY_SCL_PIN GPIO_NUM_15 +#define DISPLAY_WIDTH 128 + +#if CONFIG_OLED_SSD1306_128X32 +#define DISPLAY_HEIGHT 32 +#elif CONFIG_OLED_SSD1306_128X64 +#define DISPLAY_HEIGHT 64 +#else +#error "未选择 OLED 屏幕类型" +#endif + +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_18 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-esp32/config.json b/main/boards/bread-compact-esp32/config.json new file mode 100644 index 0000000..9a7dd55 --- /dev/null +++ b/main/boards/bread-compact-esp32/config.json @@ -0,0 +1,17 @@ +{ + "target": "esp32", + "builds": [ + { + "name": "bread-compact-esp32", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X64=y" + ] + }, + { + "name": "bread-compact-esp32-128x32", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X32=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/bread-compact-esp32/esp32_bread_board.cc b/main/boards/bread-compact-esp32/esp32_bread_board.cc new file mode 100644 index 0000000..31c08c8 --- /dev/null +++ b/main/boards/bread-compact-esp32/esp32_bread_board.cc @@ -0,0 +1,174 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "display/oled_display.h" + +#include +#include +#include +#include +#include + +#define TAG "ESP32-MarsbearSupport" + +class CompactWifiBoard : public DualNetworkBoard { +private: + Button boot_button_; + Button touch_button_; + Button asr_button_; + + i2c_master_bus_handle_t display_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + + // 配置 GPIO + gpio_config_t io_conf = { + .pin_bit_mask = 1ULL << BUILTIN_LED_GPIO, // 设置需要配置的 GPIO 引脚 + .mode = GPIO_MODE_OUTPUT, // 设置为输出模式 + .pull_up_en = GPIO_PULLUP_DISABLE, // 禁用上拉 + .pull_down_en = GPIO_PULLDOWN_DISABLE, // 禁用下拉 + .intr_type = GPIO_INTR_DISABLE // 禁用中断 + }; + gpio_config(&io_conf); // 应用配置 + + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + gpio_set_level(BUILTIN_LED_GPIO, 1); + app.ToggleChatState(); + }); + + + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + asr_button_.OnClick([this]() { + std::string wake_word="你好小智"; + Application::GetInstance().WakeWordInvoke(wake_word); + }); + + touch_button_.OnPressDown([this]() { + gpio_set_level(BUILTIN_LED_GPIO, 1); + Application::GetInstance().StartListening(); + }); + touch_button_.OnPressUp([this]() { + gpio_set_level(BUILTIN_LED_GPIO, 0); + Application::GetInstance().StopListening(); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + CompactWifiBoard() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), boot_button_(BOOT_BUTTON_GPIO), touch_button_(TOUCH_BUTTON_GPIO), asr_button_(ASR_BUTTON_GPIO) + { + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override + { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + +}; + +DECLARE_BOARD(CompactWifiBoard); diff --git a/main/boards/bread-compact-ml307/compact_ml307_board.cc b/main/boards/bread-compact-ml307/compact_ml307_board.cc new file mode 100644 index 0000000..e004b55 --- /dev/null +++ b/main/boards/bread-compact-ml307/compact_ml307_board.cc @@ -0,0 +1,191 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "display/oled_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include + +#define TAG "CompactMl307Board" + +class CompactMl307Board : public DualNetworkBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + Button touch_button_; + Button volume_up_button_; + Button volume_down_button_; + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + touch_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + touch_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + volume_up_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + CompactMl307Board() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN, GPIO_NUM_NC), + boot_button_(BOOT_BUTTON_GPIO), + touch_button_(TOUCH_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(CompactMl307Board); diff --git a/main/boards/bread-compact-ml307/config.h b/main/boards/bread-compact-ml307/config.h new file mode 100644 index 0000000..de9ef7f --- /dev/null +++ b/main/boards/bread-compact-ml307/config.h @@ -0,0 +1,59 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_47 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA_PIN GPIO_NUM_41 +#define DISPLAY_SCL_PIN GPIO_NUM_42 +#define DISPLAY_WIDTH 128 + +#if CONFIG_OLED_SSD1306_128X32 +#define DISPLAY_HEIGHT 32 +#elif CONFIG_OLED_SSD1306_128X64 +#define DISPLAY_HEIGHT 64 +#else +#error "未选择 OLED 屏幕类型" +#endif + +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_18 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-ml307/config.json b/main/boards/bread-compact-ml307/config.json new file mode 100644 index 0000000..9da8cab --- /dev/null +++ b/main/boards/bread-compact-ml307/config.json @@ -0,0 +1,17 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "bread-compact-ml307", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X32=y" + ] + }, + { + "name": "bread-compact-ml307-128x64", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X64=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/bread-compact-wifi-lcd/compact_wifi_board_lcd.cc b/main/boards/bread-compact-wifi-lcd/compact_wifi_board_lcd.cc new file mode 100644 index 0000000..5e0263e --- /dev/null +++ b/main/boards/bread-compact-wifi-lcd/compact_wifi_board_lcd.cc @@ -0,0 +1,183 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include +#include +#include + +#if defined(LCD_TYPE_ILI9341_SERIAL) +#include "esp_lcd_ili9341.h" +#endif + +#if defined(LCD_TYPE_GC9A01_SERIAL) +#include "esp_lcd_gc9a01.h" +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; +#endif + +#define TAG "CompactWifiBoardLCD" + +class CompactWifiBoardLCD : public WifiBoard { +private: + + Button boot_button_; + LcdDisplay* display_; + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; +#if defined(LCD_TYPE_ILI9341_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); +#elif defined(LCD_TYPE_GC9A01_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel)); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; +#else + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); +#endif + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); +#ifdef LCD_TYPE_GC9A01_SERIAL + panel_config.vendor_config = &gc9107_vendor_config; +#endif + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + CompactWifiBoardLCD() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } +}; + +DECLARE_BOARD(CompactWifiBoardLCD); diff --git a/main/boards/bread-compact-wifi-lcd/config.h b/main/boards/bread-compact-wifi-lcd/config.h new file mode 100644 index 0000000..12d3802 --- /dev/null +++ b/main/boards/bread-compact-wifi-lcd/config.h @@ -0,0 +1,289 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_42 +#define DISPLAY_MOSI_PIN GPIO_NUM_47 +#define DISPLAY_CLK_PIN GPIO_NUM_21 +#define DISPLAY_DC_PIN GPIO_NUM_40 +#define DISPLAY_RST_PIN GPIO_NUM_45 +#define DISPLAY_CS_PIN GPIO_NUM_41 + + +#ifdef CONFIG_LCD_ST7789_240X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X320_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_170X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 170 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 35 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_172X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 172 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 34 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X280 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240_7PIN +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 3 +#endif + +#ifdef CONFIG_LCD_ST7789_240X135 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 135 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 40 +#define DISPLAY_OFFSET_Y 53 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X160 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X128 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 32 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320 +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320_NO_IPS +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_GC9A01_240X240 +#define LCD_TYPE_GC9A01_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_CUSTOM +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_18 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-wifi-s3cam/README.md b/main/boards/bread-compact-wifi-s3cam/README.md new file mode 100644 index 0000000..51e7fdc --- /dev/null +++ b/main/boards/bread-compact-wifi-s3cam/README.md @@ -0,0 +1,51 @@ +硬件基于基于ESP32S3CAM开发板,代码基于bread-compact-wifi-lcd修改 +使用的摄像头是OV2640 +注意因为摄像头占用IO较多,所以占用了ESP32S3的USB 19 20两个引脚 +连线方式参考config.h文件中对引脚的定义 + + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +```bash +Xiaozhi Assistant -> Board Type ->面包板新版接线(WiFi)+ LCD + Camera +``` + +**配置摄像头传感器:** + +> **注意:** 确认摄像头传感器型号,确定型号在 esp_cam_sensor 支持的范围内。当前板子用的是 OV2640,是符合支持范围。 + +在 menuconfig 中按以下步骤启用对应型号的支持: + +1. **导航到传感器配置:** + ``` + (Top) → Component config → Espressif Camera Sensors Configurations → Camera Sensor Configuration → Select and Set Camera Sensor + ``` + +2. **选择传感器型号:** + - 选中所需的传感器型号(OV2640) + +3. **配置传感器参数:** + - 按 → 进入传感器详细设置 + - 启用 **Auto detect** + - 推荐将 **default output format** 调整为 **YUV422** 及合适的分辨率大小 + - (目前支持 YUV422、RGB565,YUV422 更节省内存空间) + +**编译烧入:** + +```bash +idf.py build flash +``` \ No newline at end of file diff --git a/main/boards/bread-compact-wifi-s3cam/compact_wifi_board_s3cam.cc b/main/boards/bread-compact-wifi-s3cam/compact_wifi_board_s3cam.cc new file mode 100644 index 0000000..adf41f9 --- /dev/null +++ b/main/boards/bread-compact-wifi-s3cam/compact_wifi_board_s3cam.cc @@ -0,0 +1,282 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "esp32_camera.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "esp_log.h" +#include "esp_rom_sys.h" + +#if defined(LCD_TYPE_ILI9341_SERIAL) +#include "esp_lcd_ili9341.h" +#endif + +#if defined(LCD_TYPE_GC9A01_SERIAL) +#include "esp_lcd_gc9a01.h" +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; +#endif + +// --- START CORRECTED DUMMY DISPLAY CLASS --- +#include "display/display.h" + +class DummyDisplay : public Display { +public: + // Fix 1: Use the correct base constructor (no arguments) + DummyDisplay() : Display() {} + + // Fix 2: Implement the required "Pure Virtual" functions + // (These were missing, causing the "abstract class" error) + bool Lock(int timeout_ms = 0) override { return true; } + void Unlock() override {} + + // Fix 3: Correct signatures for Notifications (Return void, accept duration) + // We override both versions (string and char*) to be safe. + void ShowNotification(const std::string ¬ification, int duration_ms = 3000) override {} + void ShowNotification(const char* notification, int duration_ms = 3000) override {} + + // Fix 4: Correct signature for Chat Message (Must use const char*) + void SetChatMessage(const char* role, const char* content) override {} + + // Note: We removed ShowStatus, SetIcon, Update, Draw, and Clear. + // The error logs indicated these are not virtual in the base class, + // so we don't need to (and cannot) override them. + // We simply inherit the empty/default behavior for those. +}; +// --- END CORRECTED DUMMY DISPLAY CLASS --- + +#define TAG "CompactWifiBoardS3Cam" + +class CompactWifiBoardS3Cam : public WifiBoard { +private: + + Button boot_button_; + Display* display_; + Esp32Camera* camera_; + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; +#if defined(LCD_TYPE_ILI9341_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); +#elif defined(LCD_TYPE_GC9A01_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel)); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; +#else + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); +#endif + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); +#ifdef LCD_TYPE_GC9A01_SERIAL + panel_config.vendor_config = &gc9107_vendor_config; +#endif + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + esp_log_level_set("Esp32Camera", ESP_LOG_DEBUG); + esp_log_level_set("esp_video", ESP_LOG_DEBUG); + esp_log_level_set("video", ESP_LOG_DEBUG); + + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 0, + .scl_pin = CAMERA_PIN_SIOC, + .sda_pin = CAMERA_PIN_SIOD, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + esp_rom_delay_us(20000); // 20 ms + camera_ = new Esp32Camera(video_config); + ESP_LOGE("CAM", "camera ptr: %p", camera_); + + + + camera_->SetHMirror(true); + camera_->SetVFlip(true); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + CompactWifiBoardS3Cam() : + boot_button_(BOOT_BUTTON_GPIO) { + + // FIX 1: Force release JTAG pins (39-42) for GPIO use + // This effectively disconnects the debugger so the Camera (39/40) + // and LED (41) can use these pins. + gpio_reset_pin(GPIO_NUM_39); + gpio_reset_pin(GPIO_NUM_40); + gpio_reset_pin(GPIO_NUM_41); + gpio_reset_pin(GPIO_NUM_42); + + InitializeSpi(); + // InitializeLcdDisplay(); + + display_ = new DummyDisplay(); + + InitializeButtons(); + InitializeCamera(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(CompactWifiBoardS3Cam); diff --git a/main/boards/bread-compact-wifi-s3cam/config.h b/main/boards/bread-compact-wifi-s3cam/config.h new file mode 100644 index 0000000..53a308c --- /dev/null +++ b/main/boards/bread-compact-wifi-s3cam/config.h @@ -0,0 +1,333 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 // checked for CogNog V1.0 - original NUM_1 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 // checked for CogNog V1.0 - original NUM_2 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 // checked for CogNog V1.0 - original NUM_42 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 // checked for CogNog V1.0 - original NUM_39 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 // checked for CogNog V1.0 - original NUM_40 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 // checked for CogNog V1.0 - original NUM_41 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + + +#define BUILTIN_LED_GPIO GPIO_NUM_3 //changes from 48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +//Camera Config +#define CAMERA_PIN_D0 GPIO_NUM_11 // checked for CogNog V1.0 +#define CAMERA_PIN_D1 GPIO_NUM_9 // checked for CogNog V1.0 +#define CAMERA_PIN_D2 GPIO_NUM_8 // checked for CogNog V1.0 +#define CAMERA_PIN_D3 GPIO_NUM_10 // checked for CogNog V1.0 +#define CAMERA_PIN_D4 GPIO_NUM_12 // checked for CogNog V1.0 +#define CAMERA_PIN_D5 GPIO_NUM_39 // checked for CogNog V1.0 - original NUM_18 +#define CAMERA_PIN_D6 GPIO_NUM_40 // checked for CogNog V1.0 - original NUM_17 +#define CAMERA_PIN_D7 GPIO_NUM_14 // checked for CogNog V1.0 - original NUM_16 << REWIRED IN PROTOTYPE P2 << 35->14 +#define CAMERA_PIN_XCLK GPIO_NUM_21 // checked for CogNog V1.0 - original NUM_15 +#define CAMERA_PIN_PCLK GPIO_NUM_13 // checked for CogNog V1.0 +#define CAMERA_PIN_VSYNC GPIO_NUM_41 // checked for CogNog V1.0 - original NUM_6 << REWIRED IN PROTOTYPE P2 << 36->41 +#define CAMERA_PIN_HREF GPIO_NUM_42 // checked for CogNog V1.0 - original NUM_7 << REWIRED IN PROTOTYPE P2 << 37->42 +#define CAMERA_PIN_SIOC GPIO_NUM_47 // checked for CogNog V1.0 - original NUM_5 +#define CAMERA_PIN_SIOD GPIO_NUM_48 // checked for CogNog V1.0 - original NUM_4 +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define XCLK_FREQ_HZ 20000000 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC // checked +#define DISPLAY_MOSI_PIN GPIO_NUM_NC // checked - original NUM_20 +#define DISPLAY_DC_PIN GPIO_NUM_NC // checked - original NUM_47 +#define DISPLAY_RST_PIN GPIO_NUM_NC // checked - original NUM_21 +#define DISPLAY_CS_PIN GPIO_NUM_NC // checked - original NUM_47 + +#define DISPLAY_CLK_PIN GPIO_NUM_NC // I dont know whats going on here + +// // Not sure about any of this ... + +// #define DISPLAY_SDA_PIN GPIO_NUM_41 +// #define DISPLAY_SCL_PIN GPIO_NUM_42 +// #define DISPLAY_WIDTH 128 + +// #if CONFIG_OLED_SSD1306_128X32 +// #define DISPLAY_HEIGHT 32 +// #elif CONFIG_OLED_SSD1306_128X64 +// #define DISPLAY_HEIGHT 64 +// #elif CONFIG_OLED_SH1106_128X64 +// #define DISPLAY_HEIGHT 64 +// #define SH1106 +// #else +// #error "未选择 OLED 屏幕类型" +// #endif + +// #define DISPLAY_MIRROR_X true +// #define DISPLAY_MIRROR_Y true + +// // Not sure about any of this ^^^ + + + + + +#ifdef CONFIG_LCD_ST7789_240X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X320_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_170X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 170 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 35 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_172X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 172 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 34 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X280 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240_7PIN +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 3 +#endif + +#ifdef CONFIG_LCD_ST7789_240X135 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 135 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 40 +#define DISPLAY_OFFSET_Y 53 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X160 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X128 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 32 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320 +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320_NO_IPS +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_GC9A01_240X240 +#define LCD_TYPE_GC9A01_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_CUSTOM +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_2 //changed from 14 tp 2 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-wifi/compact_wifi_board.cc b/main/boards/bread-compact-wifi/compact_wifi_board.cc new file mode 100644 index 0000000..fca4d1c --- /dev/null +++ b/main/boards/bread-compact-wifi/compact_wifi_board.cc @@ -0,0 +1,188 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/oled_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include + +#ifdef SH1106 +#include +#endif + +#define TAG "CompactWifiBoard" + +class CompactWifiBoard : public WifiBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + Button touch_button_; + Button volume_up_button_; + Button volume_down_button_; + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + +#ifdef SH1106 + ESP_ERROR_CHECK(esp_lcd_new_panel_sh1106(panel_io_, &panel_config, &panel_)); +#else + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); +#endif + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, false)); + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + touch_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + touch_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + volume_up_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + // 物联网初始化,逐步迁移到 MCP 协议 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + CompactWifiBoard() : + boot_button_(BOOT_BUTTON_GPIO), + touch_button_(TOUCH_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(CompactWifiBoard); diff --git a/main/boards/bread-compact-wifi/config.h b/main/boards/bread-compact-wifi/config.h new file mode 100644 index 0000000..7bb0982 --- /dev/null +++ b/main/boards/bread-compact-wifi/config.h @@ -0,0 +1,59 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_47 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA_PIN GPIO_NUM_41 +#define DISPLAY_SCL_PIN GPIO_NUM_42 +#define DISPLAY_WIDTH 128 + +#if CONFIG_OLED_SSD1306_128X32 +#define DISPLAY_HEIGHT 32 +#elif CONFIG_OLED_SSD1306_128X64 +#define DISPLAY_HEIGHT 64 +#elif CONFIG_OLED_SH1106_128X64 +#define DISPLAY_HEIGHT 64 +#define SH1106 +#else +#error "未选择 OLED 屏幕类型" +#endif + +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_18 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/bread-compact-wifi/config.json b/main/boards/bread-compact-wifi/config.json new file mode 100644 index 0000000..ea296f9 --- /dev/null +++ b/main/boards/bread-compact-wifi/config.json @@ -0,0 +1,17 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "bread-compact-wifi", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X32=y" + ] + }, + { + "name": "bread-compact-wifi-128x64", + "sdkconfig_append": [ + "CONFIG_OLED_SSD1306_128X64=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/common/adc_battery_monitor.cc b/main/boards/common/adc_battery_monitor.cc new file mode 100644 index 0000000..c34da68 --- /dev/null +++ b/main/boards/common/adc_battery_monitor.cc @@ -0,0 +1,116 @@ +#include "adc_battery_monitor.h" + +AdcBatteryMonitor::AdcBatteryMonitor(adc_unit_t adc_unit, adc_channel_t adc_channel, float upper_resistor, float lower_resistor, gpio_num_t charging_pin) + : charging_pin_(charging_pin) { + + // Initialize charging pin (only if it's not NC) + if (charging_pin_ != GPIO_NUM_NC) { + gpio_config_t gpio_cfg = { + .pin_bit_mask = 1ULL << charging_pin, + .mode = GPIO_MODE_INPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + ESP_ERROR_CHECK(gpio_config(&gpio_cfg)); + } + + // Initialize ADC battery estimation + adc_battery_estimation_t adc_cfg = { + .internal = { + .adc_unit = adc_unit, + .adc_bitwidth = ADC_BITWIDTH_DEFAULT, + .adc_atten = ADC_ATTEN_DB_12, + }, + .adc_channel = adc_channel, + .upper_resistor = upper_resistor, + .lower_resistor = lower_resistor + }; + + // 在ADC配置部分进行条件设置 + if (charging_pin_ != GPIO_NUM_NC) { + adc_cfg.charging_detect_cb = [](void *user_data) -> bool { + AdcBatteryMonitor *self = (AdcBatteryMonitor *)user_data; + return gpio_get_level(self->charging_pin_) == 1; + }; + adc_cfg.charging_detect_user_data = this; + } else { + // 不设置回调,让adc_battery_estimation库使用软件估算 + adc_cfg.charging_detect_cb = nullptr; + adc_cfg.charging_detect_user_data = nullptr; + } + adc_battery_estimation_handle_ = adc_battery_estimation_create(&adc_cfg); + + // Initialize timer + esp_timer_create_args_t timer_cfg = { + .callback = [](void *arg) { + AdcBatteryMonitor *self = (AdcBatteryMonitor *)arg; + self->CheckBatteryStatus(); + }, + .arg = this, + .name = "adc_battery_monitor", + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_cfg, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); +} + +AdcBatteryMonitor::~AdcBatteryMonitor() { + if (adc_battery_estimation_handle_) { + ESP_ERROR_CHECK(adc_battery_estimation_destroy(adc_battery_estimation_handle_)); + } + + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } +} + +bool AdcBatteryMonitor::IsCharging() { + // 优先使用adc_battery_estimation库的功能 + if (adc_battery_estimation_handle_ != nullptr) { + bool is_charging = false; + esp_err_t err = adc_battery_estimation_get_charging_state(adc_battery_estimation_handle_, &is_charging); + if (err == ESP_OK) { + return is_charging; + } + } + + // 回退到GPIO读取或返回默认值 + if (charging_pin_ != GPIO_NUM_NC) { + return gpio_get_level(charging_pin_) == 1; + } + + return false; +} + +bool AdcBatteryMonitor::IsDischarging() { + return !IsCharging(); +} + +uint8_t AdcBatteryMonitor::GetBatteryLevel() { + // 如果句柄无效,返回默认值 + if (adc_battery_estimation_handle_ == nullptr) { + return 100; + } + + float capacity = 0; + esp_err_t err = adc_battery_estimation_get_capacity(adc_battery_estimation_handle_, &capacity); + if (err != ESP_OK) { + return 100; // 出错时返回默认值 + } + return (uint8_t)capacity; +} + +void AdcBatteryMonitor::OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; +} + +void AdcBatteryMonitor::CheckBatteryStatus() { + bool new_charging_status = IsCharging(); + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + } +} \ No newline at end of file diff --git a/main/boards/common/adc_battery_monitor.h b/main/boards/common/adc_battery_monitor.h new file mode 100644 index 0000000..6a123a7 --- /dev/null +++ b/main/boards/common/adc_battery_monitor.h @@ -0,0 +1,30 @@ +#ifndef ADC_BATTERY_MONITOR_H +#define ADC_BATTERY_MONITOR_H + +#include +#include +#include +#include + +class AdcBatteryMonitor { +public: + AdcBatteryMonitor(adc_unit_t adc_unit, adc_channel_t adc_channel, float upper_resistor, float lower_resistor, gpio_num_t charging_pin = GPIO_NUM_NC); + ~AdcBatteryMonitor(); + + bool IsCharging(); + bool IsDischarging(); + uint8_t GetBatteryLevel(); + + void OnChargingStatusChanged(std::function callback); + +private: + gpio_num_t charging_pin_; + adc_battery_estimation_handle_t adc_battery_estimation_handle_ = nullptr; + esp_timer_handle_t timer_handle_ = nullptr; + bool is_charging_ = false; + std::function on_charging_status_changed_; + + void CheckBatteryStatus(); +}; + +#endif // ADC_BATTERY_MONITOR_H diff --git a/main/boards/common/afsk_demod.cc b/main/boards/common/afsk_demod.cc new file mode 100644 index 0000000..9e040de --- /dev/null +++ b/main/boards/common/afsk_demod.cc @@ -0,0 +1,371 @@ +#include "afsk_demod.h" +#include +#include +#include "esp_log.h" +#include "display.h" + +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif + +namespace audio_wifi_config +{ + static const char *kLogTag = "AUDIO_WIFI_CONFIG"; + + void ReceiveWifiCredentialsFromAudio(Application *app, + WifiConfigurationAp *wifi_ap, + Display *display, + size_t input_channels + ) + { + const int kInputSampleRate = 16000; // Input sampling rate + const float kDownsampleStep = static_cast(kInputSampleRate) / static_cast(kAudioSampleRate); // Downsampling step + std::vector audio_data; + AudioSignalProcessor signal_processor(kAudioSampleRate, kMarkFrequency, kSpaceFrequency, kBitRate, kWindowSize); + AudioDataBuffer data_buffer; + + while (true) + { + // 检查Application状态,只有在WiFi配置模式下才处理音频 + if (app->GetDeviceState() != kDeviceStateWifiConfiguring) { + // 不在WiFi配置状态,休眠100ms后再检查 + vTaskDelay(pdMS_TO_TICKS(100)); + continue; + } + + if (!app->GetAudioService().ReadAudioData(audio_data, 16000, 480)) { // 16kHz, 480 samples corresponds to 30ms data + // 读取音频失败,短暂延迟后重试 + ESP_LOGI(kLogTag, "Failed to read audio data, retrying."); + vTaskDelay(pdMS_TO_TICKS(10)); + continue; + } + + if (input_channels == 2) { // 如果是双声道输入,转换为单声道 + auto mono_data = std::vector(audio_data.size() / 2); + for (size_t i = 0, j = 0; i < mono_data.size(); ++i, j += 2) { + mono_data[i] = audio_data[j]; + } + audio_data = std::move(mono_data); + } + + // Downsample the audio data + std::vector downsampled_data; + size_t last_index = 0; + + if (kDownsampleStep > 1.0f) { + downsampled_data.reserve(audio_data.size() / static_cast(kDownsampleStep)); + for (size_t i = 0; i < audio_data.size(); ++i) { + size_t sample_index = static_cast(i / kDownsampleStep); + if ((sample_index + 1) > last_index) { + downsampled_data.push_back(static_cast(audio_data[i])); + last_index = sample_index + 1; + } + } + } else { + downsampled_data.reserve(audio_data.size()); + for (int16_t sample : audio_data) { + downsampled_data.push_back(static_cast(sample)); + } + } + + // Process audio samples to get probability data + auto probabilities = signal_processor.ProcessAudioSamples(downsampled_data); + + // Feed probability data to the data buffer + if (data_buffer.ProcessProbabilityData(probabilities, 0.5f)) { + // If complete data was received, extract WiFi credentials + if (data_buffer.decoded_text.has_value()) { + ESP_LOGI(kLogTag, "Received text data: %s", data_buffer.decoded_text->c_str()); + display->SetChatMessage("system", data_buffer.decoded_text->c_str()); + + // Split SSID and password by newline character + std::string wifi_ssid, wifi_password; + size_t newline_position = data_buffer.decoded_text->find('\n'); + if (newline_position != std::string::npos) { + wifi_ssid = data_buffer.decoded_text->substr(0, newline_position); + wifi_password = data_buffer.decoded_text->substr(newline_position + 1); + ESP_LOGI(kLogTag, "WiFi SSID: %s, Password: %s", wifi_ssid.c_str(), wifi_password.c_str()); + } else { + ESP_LOGE(kLogTag, "Invalid data format, no newline character found"); + continue; + } + + if (wifi_ap->ConnectToWifi(wifi_ssid, wifi_password)) { + wifi_ap->Save(wifi_ssid, wifi_password); // Save WiFi credentials + esp_restart(); // Restart device to apply new WiFi configuration + } else { + ESP_LOGE(kLogTag, "Failed to connect to WiFi with received credentials"); + } + data_buffer.decoded_text.reset(); // Clear processed data + } + } + vTaskDelay(pdMS_TO_TICKS(1)); // 1ms delay + } + } + + // Default start and end transmission identifiers + // \x01\x02 = 00000001 00000010 + const std::vector kDefaultStartTransmissionPattern = { + 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0}; + + // \x03\x04 = 00000011 00000100 + const std::vector kDefaultEndTransmissionPattern = { + 0, 0, 0, 0, 0, 0, 1, 1, 0, 0, 0, 0, 0, 1, 0, 0}; + + // FrequencyDetector implementation + FrequencyDetector::FrequencyDetector(float frequency, size_t window_size) + : frequency_(frequency), window_size_(window_size) { + frequency_bin_ = std::floor(frequency_ * static_cast(window_size_)); + angular_frequency_ = 2.0f * M_PI * frequency_; + cos_coefficient_ = std::cos(angular_frequency_); + sin_coefficient_ = std::sin(angular_frequency_); + filter_coefficient_ = 2.0f * cos_coefficient_; + + // Initialize state buffer + state_buffer_.push_back(0.0f); + state_buffer_.push_back(0.0f); + } + + void FrequencyDetector::Reset() { + state_buffer_.clear(); + state_buffer_.push_back(0.0f); + state_buffer_.push_back(0.0f); + } + + void FrequencyDetector::ProcessSample(float sample) { + if (state_buffer_.size() < 2) { + return; + } + + float s_minus_2 = state_buffer_.front(); // S[-2] + state_buffer_.pop_front(); + float s_minus_1 = state_buffer_.front(); // S[-1] + state_buffer_.pop_front(); + + float s_current = sample + filter_coefficient_ * s_minus_1 - s_minus_2; + + state_buffer_.push_back(s_minus_1); // Put S[-1] back + state_buffer_.push_back(s_current); // Add new S[0] + } + + float FrequencyDetector::GetAmplitude() const { + if (state_buffer_.size() < 2) { + return 0.0f; + } + + float s_minus_1 = state_buffer_[1]; // S[-1] + float s_minus_2 = state_buffer_[0]; // S[-2] + float real_part = cos_coefficient_ * s_minus_1 - s_minus_2; // Real part + float imaginary_part = sin_coefficient_ * s_minus_1; // Imaginary part + + return std::sqrt(real_part * real_part + imaginary_part * imaginary_part) / + (static_cast(window_size_) / 2.0f); + } + + // AudioSignalProcessor implementation + AudioSignalProcessor::AudioSignalProcessor(size_t sample_rate, size_t mark_frequency, size_t space_frequency, + size_t bit_rate, size_t window_size) + : input_buffer_size_(window_size), output_sample_count_(0) { + if (sample_rate % bit_rate != 0) { + // On ESP32 we can continue execution, but log the error + ESP_LOGW(kLogTag, "Sample rate %zu is not divisible by bit rate %zu", sample_rate, bit_rate); + } + + float normalized_mark_freq = static_cast(mark_frequency) / static_cast(sample_rate); + float normalized_space_freq = static_cast(space_frequency) / static_cast(sample_rate); + + mark_detector_ = std::make_unique(normalized_mark_freq, window_size); + space_detector_ = std::make_unique(normalized_space_freq, window_size); + + samples_per_bit_ = sample_rate / bit_rate; // Number of samples per bit + } + + std::vector AudioSignalProcessor::ProcessAudioSamples(const std::vector &samples) { + std::vector result; + + for (float sample : samples) { + if (input_buffer_.size() < input_buffer_size_) { + input_buffer_.push_back(sample); // Just add, don't process yet + } else { + // Input buffer is full, process the data + input_buffer_.pop_front(); // Remove oldest sample + input_buffer_.push_back(sample); // Add new sample + output_sample_count_++; + + if (output_sample_count_ >= samples_per_bit_) { + // Process all samples in the window using Goertzel algorithm + for (float window_sample : input_buffer_) { + mark_detector_->ProcessSample(window_sample); + space_detector_->ProcessSample(window_sample); + } + + float mark_amplitude = mark_detector_->GetAmplitude(); // Mark amplitude + float space_amplitude = space_detector_->GetAmplitude(); // Space amplitude + + // Avoid division by zero + float mark_probability = mark_amplitude / + (space_amplitude + mark_amplitude + std::numeric_limits::epsilon()); + result.push_back(mark_probability); + + // Reset detector windows + mark_detector_->Reset(); + space_detector_->Reset(); + output_sample_count_ = 0; // Reset output counter + } + } + } + + return result; + } + + // AudioDataBuffer implementation + AudioDataBuffer::AudioDataBuffer() + : current_state_(DataReceptionState::kInactive), + start_of_transmission_(kDefaultStartTransmissionPattern), + end_of_transmission_(kDefaultEndTransmissionPattern), + enable_checksum_validation_(true) { + identifier_buffer_size_ = std::max(start_of_transmission_.size(), end_of_transmission_.size()); + max_bit_buffer_size_ = 776; // Preset bit buffer size, 776 bits = (32 + 1 + 63 + 1) * 8 = 776 + + bit_buffer_.reserve(max_bit_buffer_size_); + } + + AudioDataBuffer::AudioDataBuffer(size_t max_byte_size, const std::vector &start_identifier, + const std::vector &end_identifier, bool enable_checksum) + : current_state_(DataReceptionState::kInactive), + start_of_transmission_(start_identifier), + end_of_transmission_(end_identifier), + enable_checksum_validation_(enable_checksum) { + identifier_buffer_size_ = std::max(start_of_transmission_.size(), end_of_transmission_.size()); + max_bit_buffer_size_ = max_byte_size * 8; // Bit buffer size in bytes + + bit_buffer_.reserve(max_bit_buffer_size_); + } + + uint8_t AudioDataBuffer::CalculateChecksum(const std::string &text) { + uint8_t checksum = 0; + for (char character : text) { + checksum += static_cast(character); + } + return checksum; + } + + void AudioDataBuffer::ClearBuffers() { + identifier_buffer_.clear(); + bit_buffer_.clear(); + } + + bool AudioDataBuffer::ProcessProbabilityData(const std::vector &probabilities, float threshold) { + for (float probability : probabilities) { + uint8_t bit = (probability > threshold) ? 1 : 0; + + if (identifier_buffer_.size() >= identifier_buffer_size_) { + identifier_buffer_.pop_front(); // Maintain buffer size + } + identifier_buffer_.push_back(bit); + + // Process received bit based on state machine + switch (current_state_) { + case DataReceptionState::kInactive: + if (identifier_buffer_.size() >= start_of_transmission_.size()) { + current_state_ = DataReceptionState::kWaiting; // Enter waiting state + ESP_LOGI(kLogTag, "Entering Waiting state"); + } + break; + + case DataReceptionState::kWaiting: + // Waiting state, possibly waiting for transmission end + if (identifier_buffer_.size() >= start_of_transmission_.size()) { + std::vector identifier_snapshot(identifier_buffer_.begin(), identifier_buffer_.end()); + if (identifier_snapshot == start_of_transmission_) + { + ClearBuffers(); // Clear buffers + current_state_ = DataReceptionState::kReceiving; // Enter receiving state + ESP_LOGI(kLogTag, "Entering Receiving state"); + } + } + break; + + case DataReceptionState::kReceiving: + bit_buffer_.push_back(bit); + if (identifier_buffer_.size() >= end_of_transmission_.size()) { + std::vector identifier_snapshot(identifier_buffer_.begin(), identifier_buffer_.end()); + if (identifier_snapshot == end_of_transmission_) { + current_state_ = DataReceptionState::kInactive; // Enter inactive state + + // Convert bits to bytes + std::vector bytes = ConvertBitsToBytes(bit_buffer_); + + uint8_t received_checksum = 0; + size_t minimum_length = 0; + + if (enable_checksum_validation_) { + // If checksum is required, last byte is checksum + minimum_length = 1 + start_of_transmission_.size() / 8; + if (bytes.size() >= minimum_length) + { + received_checksum = bytes[bytes.size() - start_of_transmission_.size() / 8 - 1]; + } + } else { + minimum_length = start_of_transmission_.size() / 8; + } + + if (bytes.size() < minimum_length) { + ClearBuffers(); + ESP_LOGW(kLogTag, "Data too short, clearing buffer"); + return false; // Data too short, return failure + } + + // Extract text data (remove trailing identifier part) + std::vector text_bytes( + bytes.begin(), bytes.begin() + bytes.size() - minimum_length); + + std::string result(text_bytes.begin(), text_bytes.end()); + + // Validate checksum if required + if (enable_checksum_validation_) { + uint8_t calculated_checksum = CalculateChecksum(result); + if (calculated_checksum != received_checksum) { + // Checksum mismatch + ESP_LOGW(kLogTag, "Checksum mismatch: expected %d, got %d", + received_checksum, calculated_checksum); + ClearBuffers(); + return false; + } + } + + ClearBuffers(); + decoded_text = result; + return true; // Return success + } else if (bit_buffer_.size() >= max_bit_buffer_size_) { + // If not end identifier and bit buffer is full, reset + ClearBuffers(); + ESP_LOGW(kLogTag, "Buffer overflow, clearing buffer"); + current_state_ = DataReceptionState::kInactive; // Reset state machine + } + } + break; + } + } + + return false; + } + + std::vector AudioDataBuffer::ConvertBitsToBytes(const std::vector &bits) const { + std::vector bytes; + + // Ensure number of bits is a multiple of 8 + size_t complete_bytes_count = bits.size() / 8; + bytes.reserve(complete_bytes_count); + + for (size_t i = 0; i < complete_bytes_count; ++i) { + uint8_t byte_value = 0; + for (size_t j = 0; j < 8; ++j) { + byte_value |= bits[i * 8 + j] << (7 - j); + } + bytes.push_back(byte_value); + } + + return bytes; + } +} diff --git a/main/boards/common/afsk_demod.h b/main/boards/common/afsk_demod.h new file mode 100644 index 0000000..87b3805 --- /dev/null +++ b/main/boards/common/afsk_demod.h @@ -0,0 +1,177 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include "wifi_configuration_ap.h" +#include "application.h" + +// Audio signal processing constants for WiFi configuration via audio +const size_t kAudioSampleRate = 6400; +const size_t kMarkFrequency = 1800; +const size_t kSpaceFrequency = 1500; +const size_t kBitRate = 100; +const size_t kWindowSize = 64; + +namespace audio_wifi_config +{ + // Main function to receive WiFi credentials through audio signal + void ReceiveWifiCredentialsFromAudio(Application *app, WifiConfigurationAp *wifi_ap, Display *display, + size_t input_channels = 1); + + /** + * Goertzel algorithm implementation for single frequency detection + * Used to detect specific audio frequencies in the AFSK demodulation process + */ + class FrequencyDetector + { + private: + float frequency_; // Target frequency (normalized, i.e., f / fs) + size_t window_size_; // Window size for analysis + float frequency_bin_; // Frequency bin + float angular_frequency_; // Angular frequency + float cos_coefficient_; // cos(w) + float sin_coefficient_; // sin(w) + float filter_coefficient_; // 2 * cos(w) + std::deque state_buffer_; // Circular buffer for storing S[-1] and S[-2] + + public: + /** + * Constructor + * @param frequency Normalized frequency (f / fs) + * @param window_size Window size for analysis + */ + FrequencyDetector(float frequency, size_t window_size); + + /** + * Reset the detector state + */ + void Reset(); + + /** + * Process one audio sample + * @param sample Input audio sample + */ + void ProcessSample(float sample); + + /** + * Calculate current amplitude + * @return Amplitude value + */ + float GetAmplitude() const; + }; + + /** + * Audio signal processor for Mark/Space frequency pair detection + * Processes audio signals to extract digital data using AFSK demodulation + */ + class AudioSignalProcessor + { + private: + std::deque input_buffer_; // Input sample buffer + size_t input_buffer_size_; // Input buffer size = window size + size_t output_sample_count_; // Output sample counter + size_t samples_per_bit_; // Samples per bit threshold + std::unique_ptr mark_detector_; // Mark frequency detector + std::unique_ptr space_detector_; // Space frequency detector + + public: + /** + * Constructor + * @param sample_rate Audio sampling rate + * @param mark_frequency Mark frequency for digital '1' + * @param space_frequency Space frequency for digital '0' + * @param bit_rate Data transmission bit rate + * @param window_size Analysis window size + */ + AudioSignalProcessor(size_t sample_rate, size_t mark_frequency, size_t space_frequency, + size_t bit_rate, size_t window_size); + + /** + * Process input audio samples + * @param samples Input audio sample vector + * @return Vector of Mark probability values (0.0 to 1.0) + */ + std::vector ProcessAudioSamples(const std::vector &samples); + }; + + /** + * Data reception state machine states + */ + enum class DataReceptionState + { + kInactive, // Waiting for start signal + kWaiting, // Detected potential start, waiting for confirmation + kReceiving // Actively receiving data + }; + + /** + * Data buffer for managing audio-to-digital data conversion + * Handles the complete process from audio signal to decoded text data + */ + class AudioDataBuffer + { + private: + DataReceptionState current_state_; // Current reception state + std::deque identifier_buffer_; // Buffer for start/end identifier detection + size_t identifier_buffer_size_; // Identifier buffer size + std::vector bit_buffer_; // Buffer for storing bit stream + size_t max_bit_buffer_size_; // Maximum bit buffer size + const std::vector start_of_transmission_; // Start-of-transmission identifier + const std::vector end_of_transmission_; // End-of-transmission identifier + bool enable_checksum_validation_; // Whether to validate checksum + + public: + std::optional decoded_text; // Successfully decoded text data + + /** + * Default constructor using predefined start and end identifiers + */ + AudioDataBuffer(); + + /** + * Constructor with custom parameters + * @param max_byte_size Expected maximum data size in bytes + * @param start_identifier Start-of-transmission identifier + * @param end_identifier End-of-transmission identifier + * @param enable_checksum Whether to enable checksum validation + */ + AudioDataBuffer(size_t max_byte_size, const std::vector &start_identifier, + const std::vector &end_identifier, bool enable_checksum = false); + + /** + * Process probability data and attempt to decode + * @param probabilities Vector of Mark probabilities + * @param threshold Decision threshold for bit detection + * @return true if complete data was successfully received and decoded + */ + bool ProcessProbabilityData(const std::vector &probabilities, float threshold = 0.5f); + + /** + * Calculate checksum for ASCII text + * @param text Input text string + * @return Checksum value (0-255) + */ + static uint8_t CalculateChecksum(const std::string &text); + + private: + /** + * Convert bit vector to byte vector + * @param bits Input bit vector + * @return Converted byte vector + */ + std::vector ConvertBitsToBytes(const std::vector &bits) const; + + /** + * Clear all buffers and reset state + */ + void ClearBuffers(); + }; + + // Default start and end transmission identifiers + extern const std::vector kDefaultStartTransmissionPattern; + extern const std::vector kDefaultEndTransmissionPattern; +} \ No newline at end of file diff --git a/main/boards/common/axp2101.cc b/main/boards/common/axp2101.cc new file mode 100644 index 0000000..854f0b8 --- /dev/null +++ b/main/boards/common/axp2101.cc @@ -0,0 +1,41 @@ +#include "axp2101.h" +#include "board.h" +#include "display.h" + +#include + +#define TAG "Axp2101" + +Axp2101::Axp2101(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { +} + +int Axp2101::GetBatteryCurrentDirection() { + return (ReadReg(0x01) & 0b01100000) >> 5; +} + +bool Axp2101::IsCharging() { + return GetBatteryCurrentDirection() == 1; +} + +bool Axp2101::IsDischarging() { + return GetBatteryCurrentDirection() == 2; +} + +bool Axp2101::IsChargingDone() { + uint8_t value = ReadReg(0x01); + return (value & 0b00000111) == 0b00000100; +} + +int Axp2101::GetBatteryLevel() { + return ReadReg(0xA4); +} + +float Axp2101::GetTemperature() { + return ReadReg(0xA5); +} + +void Axp2101::PowerOff() { + uint8_t value = ReadReg(0x10); + value = value | 0x01; + WriteReg(0x10, value); +} diff --git a/main/boards/common/axp2101.h b/main/boards/common/axp2101.h new file mode 100644 index 0000000..473cd3e --- /dev/null +++ b/main/boards/common/axp2101.h @@ -0,0 +1,20 @@ +#ifndef __AXP2101_H__ +#define __AXP2101_H__ + +#include "i2c_device.h" + +class Axp2101 : public I2cDevice { +public: + Axp2101(i2c_master_bus_handle_t i2c_bus, uint8_t addr); + bool IsCharging(); + bool IsDischarging(); + bool IsChargingDone(); + int GetBatteryLevel(); + float GetTemperature(); + void PowerOff(); + +private: + int GetBatteryCurrentDirection(); +}; + +#endif diff --git a/main/boards/common/backlight.cc b/main/boards/common/backlight.cc new file mode 100644 index 0000000..c62fd7a --- /dev/null +++ b/main/boards/common/backlight.cc @@ -0,0 +1,121 @@ +#include "backlight.h" +#include "settings.h" + +#include +#include + +#define TAG "Backlight" + + +Backlight::Backlight() { + // 创建背光渐变定时器 + const esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + auto self = static_cast(arg); + self->OnTransitionTimer(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "backlight_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &transition_timer_)); +} + +Backlight::~Backlight() { + if (transition_timer_ != nullptr) { + esp_timer_stop(transition_timer_); + esp_timer_delete(transition_timer_); + } +} + +void Backlight::RestoreBrightness() { + // Load brightness from settings + Settings settings("display"); + int saved_brightness = settings.GetInt("brightness", 75); + + // 检查亮度值是否为0或过小,设置默认值 + if (saved_brightness <= 0) { + ESP_LOGW(TAG, "Brightness value (%d) is too small, setting to default (10)", saved_brightness); + saved_brightness = 10; // 设置一个较低的默认值 + } + + SetBrightness(saved_brightness); +} + +void Backlight::SetBrightness(uint8_t brightness, bool permanent) { + if (brightness > 100) { + brightness = 100; + } + + if (brightness_ == brightness) { + return; + } + + if (permanent) { + Settings settings("display", true); + settings.SetInt("brightness", brightness); + } + + target_brightness_ = brightness; + step_ = (target_brightness_ > brightness_) ? 1 : -1; + + if (transition_timer_ != nullptr) { + // 启动定时器,每 5ms 更新一次 + esp_timer_start_periodic(transition_timer_, 5 * 1000); + } + ESP_LOGI(TAG, "Set brightness to %d", brightness); +} + +void Backlight::OnTransitionTimer() { + if (brightness_ == target_brightness_) { + esp_timer_stop(transition_timer_); + return; + } + + brightness_ += step_; + SetBrightnessImpl(brightness_); + + if (brightness_ == target_brightness_) { + esp_timer_stop(transition_timer_); + } +} + +PwmBacklight::PwmBacklight(gpio_num_t pin, bool output_invert, uint32_t freq_hz) : Backlight() { + const ledc_timer_config_t backlight_timer = { + .speed_mode = LEDC_LOW_SPEED_MODE, + .duty_resolution = LEDC_TIMER_10_BIT, + .timer_num = LEDC_TIMER_0, + .freq_hz = freq_hz, //背光pwm频率需要高一点,防止电感啸叫 + .clk_cfg = LEDC_AUTO_CLK, + .deconfigure = false + }; + ESP_ERROR_CHECK(ledc_timer_config(&backlight_timer)); + + // Setup LEDC peripheral for PWM backlight control + const ledc_channel_config_t backlight_channel = { + .gpio_num = pin, + .speed_mode = LEDC_LOW_SPEED_MODE, + .channel = LEDC_CHANNEL_0, + .intr_type = LEDC_INTR_DISABLE, + .timer_sel = LEDC_TIMER_0, + .duty = 0, + .hpoint = 0, + .flags = { + .output_invert = output_invert, + } + }; + ESP_ERROR_CHECK(ledc_channel_config(&backlight_channel)); +} + +PwmBacklight::~PwmBacklight() { + ledc_stop(LEDC_LOW_SPEED_MODE, LEDC_CHANNEL_0, 0); +} + +void PwmBacklight::SetBrightnessImpl(uint8_t brightness) { + // LEDC resolution set to 10bits, thus: 100% = 1023 + uint32_t duty_cycle = (1023 * brightness) / 100; + ledc_set_duty(LEDC_LOW_SPEED_MODE, LEDC_CHANNEL_0, duty_cycle); + ledc_update_duty(LEDC_LOW_SPEED_MODE, LEDC_CHANNEL_0); +} + diff --git a/main/boards/common/backlight.h b/main/boards/common/backlight.h new file mode 100644 index 0000000..5c09b3d --- /dev/null +++ b/main/boards/common/backlight.h @@ -0,0 +1,36 @@ +#pragma once + +#include +#include + +#include +#include + + +class Backlight { +public: + Backlight(); + ~Backlight(); + + void RestoreBrightness(); + void SetBrightness(uint8_t brightness, bool permanent = false); + inline uint8_t brightness() const { return brightness_; } + +protected: + void OnTransitionTimer(); + virtual void SetBrightnessImpl(uint8_t brightness) = 0; + + esp_timer_handle_t transition_timer_ = nullptr; + uint8_t brightness_ = 0; + uint8_t target_brightness_ = 0; + uint8_t step_ = 1; +}; + + +class PwmBacklight : public Backlight { +public: + PwmBacklight(gpio_num_t pin, bool output_invert = false, uint32_t freq_hz = 25000); + ~PwmBacklight(); + + void SetBrightnessImpl(uint8_t brightness) override; +}; diff --git a/main/boards/common/board.cc b/main/boards/common/board.cc new file mode 100644 index 0000000..8a2f85b --- /dev/null +++ b/main/boards/common/board.cc @@ -0,0 +1,178 @@ +#include "board.h" +#include "system_info.h" +#include "settings.h" +#include "display/display.h" +#include "display/oled_display.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include + +#define TAG "Board" + +Board::Board() { + Settings settings("board", true); + uuid_ = settings.GetString("uuid"); + if (uuid_.empty()) { + uuid_ = GenerateUuid(); + settings.SetString("uuid", uuid_); + } + ESP_LOGI(TAG, "UUID=%s SKU=%s", uuid_.c_str(), BOARD_NAME); +} + +std::string Board::GenerateUuid() { + // UUID v4 需要 16 字节的随机数据 + uint8_t uuid[16]; + + // 使用 ESP32 的硬件随机数生成器 + esp_fill_random(uuid, sizeof(uuid)); + + // 设置版本 (版本 4) 和变体位 + uuid[6] = (uuid[6] & 0x0F) | 0x40; // 版本 4 + uuid[8] = (uuid[8] & 0x3F) | 0x80; // 变体 1 + + // 将字节转换为标准的 UUID 字符串格式 + char uuid_str[37]; + snprintf(uuid_str, sizeof(uuid_str), + "%02x%02x%02x%02x-%02x%02x-%02x%02x-%02x%02x-%02x%02x%02x%02x%02x%02x", + uuid[0], uuid[1], uuid[2], uuid[3], + uuid[4], uuid[5], uuid[6], uuid[7], + uuid[8], uuid[9], uuid[10], uuid[11], + uuid[12], uuid[13], uuid[14], uuid[15]); + + return std::string(uuid_str); +} + +bool Board::GetBatteryLevel(int &level, bool& charging, bool& discharging) { + return false; +} + +bool Board::GetTemperature(float& esp32temp){ + return false; +} + +Display* Board::GetDisplay() { + static NoDisplay display; + return &display; +} + +Camera* Board::GetCamera() { + return nullptr; +} + +Led* Board::GetLed() { + static NoLed led; + return &led; +} + +std::string Board::GetSystemInfoJson() { + /* + { + "version": 2, + "flash_size": 4194304, + "psram_size": 0, + "minimum_free_heap_size": 123456, + "mac_address": "00:00:00:00:00:00", + "uuid": "00000000-0000-0000-0000-000000000000", + "chip_model_name": "esp32s3", + "chip_info": { + "model": 1, + "cores": 2, + "revision": 0, + "features": 0 + }, + "application": { + "name": "my-app", + "version": "1.0.0", + "compile_time": "2021-01-01T00:00:00Z" + "idf_version": "4.2-dev" + "elf_sha256": "" + }, + "partition_table": [ + "app": { + "label": "app", + "type": 1, + "subtype": 2, + "address": 0x10000, + "size": 0x100000 + } + ], + "ota": { + "label": "ota_0" + }, + "board": { + ... + } + } + */ + std::string json = R"({"version":2,"language":")" + std::string(Lang::CODE) + R"(",)"; + json += R"("flash_size":)" + std::to_string(SystemInfo::GetFlashSize()) + R"(,)"; + json += R"("minimum_free_heap_size":")" + std::to_string(SystemInfo::GetMinimumFreeHeapSize()) + R"(",)"; + json += R"("mac_address":")" + SystemInfo::GetMacAddress() + R"(",)"; + json += R"("uuid":")" + uuid_ + R"(",)"; + json += R"("chip_model_name":")" + SystemInfo::GetChipModelName() + R"(",)"; + + esp_chip_info_t chip_info; + esp_chip_info(&chip_info); + json += R"("chip_info":{)"; + json += R"("model":)" + std::to_string(chip_info.model) + R"(,)"; + json += R"("cores":)" + std::to_string(chip_info.cores) + R"(,)"; + json += R"("revision":)" + std::to_string(chip_info.revision) + R"(,)"; + json += R"("features":)" + std::to_string(chip_info.features) + R"(},)"; + + auto app_desc = esp_app_get_description(); + json += R"("application":{)"; + json += R"("name":")" + std::string(app_desc->project_name) + R"(",)"; + json += R"("version":")" + std::string(app_desc->version) + R"(",)"; + json += R"("compile_time":")" + std::string(app_desc->date) + R"(T)" + std::string(app_desc->time) + R"(Z",)"; + json += R"("idf_version":")" + std::string(app_desc->idf_ver) + R"(",)"; + char sha256_str[65]; + for (int i = 0; i < 32; i++) { + snprintf(sha256_str + i * 2, sizeof(sha256_str) - i * 2, "%02x", app_desc->app_elf_sha256[i]); + } + json += R"("elf_sha256":")" + std::string(sha256_str) + R"(")"; + json += R"(},)"; + + json += R"("partition_table": [)"; + esp_partition_iterator_t it = esp_partition_find(ESP_PARTITION_TYPE_ANY, ESP_PARTITION_SUBTYPE_ANY, NULL); + while (it) { + const esp_partition_t *partition = esp_partition_get(it); + json += R"({)"; + json += R"("label":")" + std::string(partition->label) + R"(",)"; + json += R"("type":)" + std::to_string(partition->type) + R"(,)"; + json += R"("subtype":)" + std::to_string(partition->subtype) + R"(,)"; + json += R"("address":)" + std::to_string(partition->address) + R"(,)"; + json += R"("size":)" + std::to_string(partition->size) + R"(},)";; + it = esp_partition_next(it); + } + json.pop_back(); // Remove the last comma + json += R"(],)"; + + json += R"("ota":{)"; + auto ota_partition = esp_ota_get_running_partition(); + json += R"("label":")" + std::string(ota_partition->label) + R"(")"; + json += R"(},)"; + + // Append display info + auto display = GetDisplay(); + if (display) { + json += R"("display":{)"; + if (dynamic_cast(display)) { + json += R"("monochrome":)" + std::string("true") + R"(,)"; + } else { + json += R"("monochrome":)" + std::string("false") + R"(,)"; + } + json += R"("width":)" + std::to_string(display->width()) + R"(,)"; + json += R"("height":)" + std::to_string(display->height()) + R"(,)"; + json.pop_back(); // Remove the last comma + } + json += R"(},)"; + + json += R"("board":)" + GetBoardJson(); + + // Close the JSON object + json += R"(})"; + return json; +} diff --git a/main/boards/common/board.h b/main/boards/common/board.h new file mode 100644 index 0000000..935fed0 --- /dev/null +++ b/main/boards/common/board.h @@ -0,0 +1,62 @@ +#ifndef BOARD_H +#define BOARD_H + +#include +#include +#include +#include +#include +#include + +#include "led/led.h" +#include "backlight.h" +#include "camera.h" +#include "assets.h" + + +void* create_board(); +class AudioCodec; +class Display; +class Board { +private: + Board(const Board&) = delete; // 禁用拷贝构造函数 + Board& operator=(const Board&) = delete; // 禁用赋值操作 + +protected: + Board(); + std::string GenerateUuid(); + + // 软件生成的设备唯一标识 + std::string uuid_; + +public: + static Board& GetInstance() { + static Board* instance = static_cast(create_board()); + return *instance; + } + + virtual ~Board() = default; + virtual std::string GetBoardType() = 0; + virtual std::string GetUuid() { return uuid_; } + virtual Backlight* GetBacklight() { return nullptr; } + virtual Led* GetLed(); + virtual AudioCodec* GetAudioCodec() = 0; + virtual bool GetTemperature(float& esp32temp); + virtual Display* GetDisplay(); + virtual Camera* GetCamera(); + virtual NetworkInterface* GetNetwork() = 0; + virtual void StartNetwork() = 0; + virtual const char* GetNetworkStateIcon() = 0; + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging); + virtual std::string GetSystemInfoJson(); + virtual void SetPowerSaveMode(bool enabled) = 0; + virtual std::string GetBoardJson() = 0; + virtual std::string GetDeviceStatusJson() = 0; +}; + +#define DECLARE_BOARD(BOARD_CLASS_NAME) \ +void* create_board() { \ + return new BOARD_CLASS_NAME(); \ +} + +#endif // BOARD_H diff --git a/main/boards/common/button.cc b/main/boards/common/button.cc new file mode 100644 index 0000000..9570a5f --- /dev/null +++ b/main/boards/common/button.cc @@ -0,0 +1,125 @@ +#include "button.h" + +#include +#include + +#define TAG "Button" + +#if CONFIG_SOC_ADC_SUPPORTED +AdcButton::AdcButton(const button_adc_config_t& adc_config) : Button(nullptr) { + button_config_t btn_config = { + .long_press_time = 2000, + .short_press_time = 0, + }; + ESP_ERROR_CHECK(iot_button_new_adc_device(&btn_config, &adc_config, &button_handle_)); +} +#endif + +Button::Button(button_handle_t button_handle) : button_handle_(button_handle) { +} + +Button::Button(gpio_num_t gpio_num, bool active_high, uint16_t long_press_time, uint16_t short_press_time, bool enable_power_save) : gpio_num_(gpio_num) { + if (gpio_num == GPIO_NUM_NC) { + return; + } + button_config_t button_config = { + .long_press_time = long_press_time, + .short_press_time = short_press_time + }; + button_gpio_config_t gpio_config = { + .gpio_num = gpio_num, + .active_level = static_cast(active_high ? 1 : 0), + .enable_power_save = enable_power_save, + .disable_pull = false + }; + ESP_ERROR_CHECK(iot_button_new_gpio_device(&button_config, &gpio_config, &button_handle_)); +} + +Button::~Button() { + if (button_handle_ != NULL) { + iot_button_delete(button_handle_); + } +} + +void Button::OnPressDown(std::function callback) { + if (button_handle_ == nullptr) { + return; + } + on_press_down_ = callback; + iot_button_register_cb(button_handle_, BUTTON_PRESS_DOWN, nullptr, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_press_down_) { + button->on_press_down_(); + } + }, this); +} + +void Button::OnPressUp(std::function callback) { + if (button_handle_ == nullptr) { + return; + } + on_press_up_ = callback; + iot_button_register_cb(button_handle_, BUTTON_PRESS_UP, nullptr, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_press_up_) { + button->on_press_up_(); + } + }, this); +} + +void Button::OnLongPress(std::function callback) { + if (button_handle_ == nullptr) { + return; + } + on_long_press_ = callback; + iot_button_register_cb(button_handle_, BUTTON_LONG_PRESS_START, nullptr, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_long_press_) { + button->on_long_press_(); + } + }, this); +} + +void Button::OnClick(std::function callback) { + if (button_handle_ == nullptr) { + return; + } + on_click_ = callback; + iot_button_register_cb(button_handle_, BUTTON_SINGLE_CLICK, nullptr, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_click_) { + button->on_click_(); + } + }, this); +} + +void Button::OnDoubleClick(std::function callback) { + if (button_handle_ == nullptr) { + return; + } + on_double_click_ = callback; + iot_button_register_cb(button_handle_, BUTTON_DOUBLE_CLICK, nullptr, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_double_click_) { + button->on_double_click_(); + } + }, this); +} + +void Button::OnMultipleClick(std::function callback, uint8_t click_count) { + if (button_handle_ == nullptr) { + return; + } + on_multiple_click_ = callback; + button_event_args_t event_args = { + .multiple_clicks = { + .clicks = click_count + } + }; + iot_button_register_cb(button_handle_, BUTTON_MULTIPLE_CLICK, &event_args, [](void* handle, void* usr_data) { + Button* button = static_cast(usr_data); + if (button->on_multiple_click_) { + button->on_multiple_click_(); + } + }, this); +} \ No newline at end of file diff --git a/main/boards/common/button.h b/main/boards/common/button.h new file mode 100644 index 0000000..ceecbe5 --- /dev/null +++ b/main/boards/common/button.h @@ -0,0 +1,49 @@ +#ifndef BUTTON_H_ +#define BUTTON_H_ + +#include +#include +#include +#include +#include +#include + +class Button { +public: + Button(button_handle_t button_handle); + Button(gpio_num_t gpio_num, bool active_high = false, uint16_t long_press_time = 0, uint16_t short_press_time = 0, bool enable_power_save = false); + ~Button(); + + void OnPressDown(std::function callback); + void OnPressUp(std::function callback); + void OnLongPress(std::function callback); + void OnClick(std::function callback); + void OnDoubleClick(std::function callback); + void OnMultipleClick(std::function callback, uint8_t click_count = 3); + +protected: + gpio_num_t gpio_num_; + button_handle_t button_handle_ = nullptr; + + std::function on_press_down_; + std::function on_press_up_; + std::function on_long_press_; + std::function on_click_; + std::function on_double_click_; + std::function on_multiple_click_; +}; + +#if CONFIG_SOC_ADC_SUPPORTED +class AdcButton : public Button { +public: + AdcButton(const button_adc_config_t& adc_config); +}; +#endif + +class PowerSaveButton : public Button { +public: + PowerSaveButton(gpio_num_t gpio_num) : Button(gpio_num, false, 0, 0, true) { + } +}; + +#endif // BUTTON_H_ diff --git a/main/boards/common/camera.h b/main/boards/common/camera.h new file mode 100644 index 0000000..75c780c --- /dev/null +++ b/main/boards/common/camera.h @@ -0,0 +1,15 @@ +#ifndef CAMERA_H +#define CAMERA_H + +#include + +class Camera { +public: + virtual void SetExplainUrl(const std::string& url, const std::string& token) = 0; + virtual bool Capture() = 0; + virtual bool SetHMirror(bool enabled) = 0; + virtual bool SetVFlip(bool enabled) = 0; + virtual std::string Explain(const std::string& question) = 0; +}; + +#endif // CAMERA_H diff --git a/main/boards/common/dual_network_board.cc b/main/boards/common/dual_network_board.cc new file mode 100644 index 0000000..e6fe964 --- /dev/null +++ b/main/boards/common/dual_network_board.cc @@ -0,0 +1,93 @@ +#include "dual_network_board.h" +#include "application.h" +#include "display.h" +#include "assets/lang_config.h" +#include "settings.h" +#include + +static const char *TAG = "DualNetworkBoard"; + +DualNetworkBoard::DualNetworkBoard(gpio_num_t ml307_tx_pin, gpio_num_t ml307_rx_pin, gpio_num_t ml307_dtr_pin, int32_t default_net_type) + : Board(), + ml307_tx_pin_(ml307_tx_pin), + ml307_rx_pin_(ml307_rx_pin), + ml307_dtr_pin_(ml307_dtr_pin) { + + // 从Settings加载网络类型 + network_type_ = LoadNetworkTypeFromSettings(default_net_type); + + // 只初始化当前网络类型对应的板卡 + InitializeCurrentBoard(); +} + +NetworkType DualNetworkBoard::LoadNetworkTypeFromSettings(int32_t default_net_type) { + Settings settings("network", true); + int network_type = settings.GetInt("type", default_net_type); // 默认使用ML307 (1) + return network_type == 1 ? NetworkType::ML307 : NetworkType::WIFI; +} + +void DualNetworkBoard::SaveNetworkTypeToSettings(NetworkType type) { + Settings settings("network", true); + int network_type = (type == NetworkType::ML307) ? 1 : 0; + settings.SetInt("type", network_type); +} + +void DualNetworkBoard::InitializeCurrentBoard() { + if (network_type_ == NetworkType::ML307) { + ESP_LOGI(TAG, "Initialize ML307 board"); + current_board_ = std::make_unique(ml307_tx_pin_, ml307_rx_pin_, ml307_dtr_pin_); + } else { + ESP_LOGI(TAG, "Initialize WiFi board"); + current_board_ = std::make_unique(); + } +} + +void DualNetworkBoard::SwitchNetworkType() { + auto display = GetDisplay(); + if (network_type_ == NetworkType::WIFI) { + SaveNetworkTypeToSettings(NetworkType::ML307); + display->ShowNotification(Lang::Strings::SWITCH_TO_4G_NETWORK); + } else { + SaveNetworkTypeToSettings(NetworkType::WIFI); + display->ShowNotification(Lang::Strings::SWITCH_TO_WIFI_NETWORK); + } + vTaskDelay(pdMS_TO_TICKS(1000)); + auto& app = Application::GetInstance(); + app.Reboot(); +} + + +std::string DualNetworkBoard::GetBoardType() { + return current_board_->GetBoardType(); +} + +void DualNetworkBoard::StartNetwork() { + auto display = Board::GetInstance().GetDisplay(); + + if (network_type_ == NetworkType::WIFI) { + display->SetStatus(Lang::Strings::CONNECTING); + } else { + display->SetStatus(Lang::Strings::DETECTING_MODULE); + } + current_board_->StartNetwork(); +} + +NetworkInterface* DualNetworkBoard::GetNetwork() { + return current_board_->GetNetwork(); +} + +const char* DualNetworkBoard::GetNetworkStateIcon() { + return current_board_->GetNetworkStateIcon(); +} + +void DualNetworkBoard::SetPowerSaveMode(bool enabled) { + current_board_->SetPowerSaveMode(enabled); +} + +std::string DualNetworkBoard::GetBoardJson() { + return current_board_->GetBoardJson(); +} + +std::string DualNetworkBoard::GetDeviceStatusJson() { + return current_board_->GetDeviceStatusJson(); +} diff --git a/main/boards/common/dual_network_board.h b/main/boards/common/dual_network_board.h new file mode 100644 index 0000000..efd88a9 --- /dev/null +++ b/main/boards/common/dual_network_board.h @@ -0,0 +1,59 @@ +#ifndef DUAL_NETWORK_BOARD_H +#define DUAL_NETWORK_BOARD_H + +#include "board.h" +#include "wifi_board.h" +#include "ml307_board.h" +#include + +//enum NetworkType +enum class NetworkType { + WIFI, + ML307 +}; + +// 双网络板卡类,可以在WiFi和ML307之间切换 +class DualNetworkBoard : public Board { +private: + // 使用基类指针存储当前活动的板卡 + std::unique_ptr current_board_; + NetworkType network_type_ = NetworkType::ML307; // Default to ML307 + + // ML307的引脚配置 + gpio_num_t ml307_tx_pin_; + gpio_num_t ml307_rx_pin_; + gpio_num_t ml307_dtr_pin_; + + // 从Settings加载网络类型 + NetworkType LoadNetworkTypeFromSettings(int32_t default_net_type); + + // 保存网络类型到Settings + void SaveNetworkTypeToSettings(NetworkType type); + + // 初始化当前网络类型对应的板卡 + void InitializeCurrentBoard(); + +public: + DualNetworkBoard(gpio_num_t ml307_tx_pin, gpio_num_t ml307_rx_pin, gpio_num_t ml307_dtr_pin = GPIO_NUM_NC, int32_t default_net_type = 1); + virtual ~DualNetworkBoard() = default; + + // 切换网络类型 + void SwitchNetworkType(); + + // 获取当前网络类型 + NetworkType GetNetworkType() const { return network_type_; } + + // 获取当前活动的板卡引用 + Board& GetCurrentBoard() const { return *current_board_; } + + // 重写Board接口 + virtual std::string GetBoardType() override; + virtual void StartNetwork() override; + virtual NetworkInterface* GetNetwork() override; + virtual const char* GetNetworkStateIcon() override; + virtual void SetPowerSaveMode(bool enabled) override; + virtual std::string GetBoardJson() override; + virtual std::string GetDeviceStatusJson() override; +}; + +#endif // DUAL_NETWORK_BOARD_H \ No newline at end of file diff --git a/main/boards/common/esp32_camera.cc b/main/boards/common/esp32_camera.cc new file mode 100644 index 0000000..ab51a79 --- /dev/null +++ b/main/boards/common/esp32_camera.cc @@ -0,0 +1,1039 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "esp_imgfx_color_convert.h" +#include "esp_video_device.h" +#include "esp_video_init.h" +#include "linux/videodev2.h" + +#include "board.h" +#include "display.h" +#include "esp32_camera.h" +#include "esp_jpeg_common.h" +#include "jpg/image_to_jpeg.h" +#include "jpg/jpeg_to_image.h" +#include "lvgl_display.h" +#include "mcp_server.h" +#include "system_info.h" + +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE +#undef LOG_LOCAL_LEVEL +#define LOG_LOCAL_LEVEL MAX(CONFIG_LOG_DEFAULT_LEVEL, ESP_LOG_DEBUG) +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE +#include // should be after LOCAL_LOG_LEVEL definition + +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE +#ifdef CONFIG_IDF_TARGET_ESP32P4 +#include "driver/ppa.h" +#if defined(CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_90) +#define IMAGE_ROTATION_ANGLE (PPA_SRM_ROTATION_ANGLE_270) +#elif defined(CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_270) +#define IMAGE_ROTATION_ANGLE (PPA_SRM_ROTATION_ANGLE_90) +#else +#error "CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE is not set" +#endif // angle +#else // target +#include "esp_imgfx_rotate.h" +#if defined(CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_90) +#define IMAGE_ROTATION_ANGLE (90) +#elif defined(CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE_270) +#define IMAGE_ROTATION_ANGLE (270) +#else +#error "CONFIG_XIAOZHI_CAMERA_IMAGE_ROTATION_ANGLE is not set" +#endif // angle +#endif // target +#endif // CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + + +#define TAG "Esp32Camera" + +#if defined(CONFIG_CAMERA_SENSOR_SWAP_PIXEL_BYTE_ORDER) || defined(CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP) +#warning \ + "CAMERA_SENSOR_SWAP_PIXEL_BYTE_ORDER or CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP is enabled, which may cause image corruption in YUV422 format!" +#endif + +#if CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE +#define CAM_PRINT_FOURCC(pixelformat) \ + char fourcc[5]; \ + fourcc[0] = pixelformat & 0xFF; \ + fourcc[1] = (pixelformat >> 8) & 0xFF; \ + fourcc[2] = (pixelformat >> 16) & 0xFF; \ + fourcc[3] = (pixelformat >> 24) & 0xFF; \ + fourcc[4] = '\0'; \ + ESP_LOGD(TAG, "FOURCC: '%c%c%c%c'", fourcc[0], fourcc[1], fourcc[2], fourcc[3]); + +// for compatibility with old esp_video version +#ifndef MAP_FAILED +#define MAP_FAILED nullptr +#endif + +__attribute__((weak)) esp_err_t esp_video_deinit(void) { + return ESP_ERR_NOT_SUPPORTED; +} +// end of for compatibility with old esp_video version + +static void log_available_video_devices() { + for (int i = 0; i < 50; i++) { + char path[16]; + snprintf(path, sizeof(path), "/dev/video%d", i); + int fd = open(path, O_RDONLY); + if (fd >= 0) { + ESP_LOGD(TAG, "found video device: %s", path); + close(fd); + } + } +} +#else +#define CAM_PRINT_FOURCC(pixelformat) (void)0; +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + +Esp32Camera::Esp32Camera(const esp_video_init_config_t& config) { + if (esp_video_init(&config) != ESP_OK) { + ESP_LOGE(TAG, "esp_video_init failed"); + return; + } + +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + esp_log_level_set(TAG, ESP_LOG_DEBUG); +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + + const char* video_device_name = nullptr; + + if (false) { /* 用于构建 else if */ + } +#if CONFIG_ESP_VIDEO_ENABLE_MIPI_CSI_VIDEO_DEVICE + else if (config.csi != nullptr) { + video_device_name = ESP_VIDEO_MIPI_CSI_DEVICE_NAME; + } +#endif +#if CONFIG_ESP_VIDEO_ENABLE_DVP_VIDEO_DEVICE + else if (config.dvp != nullptr) { + video_device_name = ESP_VIDEO_DVP_DEVICE_NAME; + } +#endif +#if CONFIG_ESP_VIDEO_ENABLE_HW_JPEG_VIDEO_DEVICE + else if (config.jpeg != nullptr) { + video_device_name = ESP_VIDEO_JPEG_DEVICE_NAME; + } +#endif +#if CONFIG_ESP_VIDEO_ENABLE_SPI_VIDEO_DEVICE + else if (config.spi != nullptr) { + video_device_name = ESP_VIDEO_SPI_DEVICE_NAME; + } +#endif +#if CONFIG_ESP_VIDEO_ENABLE_USB_UVC_VIDEO_DEVICE + else if (config.usb_uvc != nullptr) { + video_device_name = ESP_VIDEO_USB_UVC_DEVICE_NAME(0); + } +#endif + + if (video_device_name == nullptr) { + ESP_LOGE(TAG, "no video device is enabled"); + return; + } + + video_fd_ = open(video_device_name, O_RDWR); + + if (video_fd_ < 0) { + ESP_LOGE(TAG, "open %s failed, errno=%d(%s)", video_device_name, errno, strerror(errno)); +#if CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + log_available_video_devices(); +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + return; + } + + struct v4l2_capability cap = {}; + if (ioctl(video_fd_, VIDIOC_QUERYCAP, &cap) != 0) { + ESP_LOGE(TAG, "VIDIOC_QUERYCAP failed, errno=%d(%s)", errno, strerror(errno)); + close(video_fd_); + video_fd_ = -1; + return; + } + + ESP_LOGD( + TAG, + "VIDIOC_QUERYCAP: driver=%s, card=%s, bus_info=%s, version=0x%08lx, capabilities=0x%08lx, device_caps=0x%08lx", + cap.driver, cap.card, cap.bus_info, cap.version, cap.capabilities, cap.device_caps); + + struct v4l2_format format = {}; + format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + if (ioctl(video_fd_, VIDIOC_G_FMT, &format) != 0) { + ESP_LOGE(TAG, "VIDIOC_G_FMT failed, errno=%d(%s)", errno, strerror(errno)); + close(video_fd_); + video_fd_ = -1; + return; + } + ESP_LOGD(TAG, "VIDIOC_G_FMT: pixelformat=0x%08lx, width=%ld, height=%ld", format.fmt.pix.pixelformat, + format.fmt.pix.width, format.fmt.pix.height); + CAM_PRINT_FOURCC(format.fmt.pix.pixelformat); + + struct v4l2_format setformat = {}; + setformat.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + sensor_width_ = format.fmt.pix.width; + sensor_height_ = format.fmt.pix.height; +#endif // CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + setformat.fmt.pix.width = format.fmt.pix.width; + setformat.fmt.pix.height = format.fmt.pix.height; + + struct v4l2_fmtdesc fmtdesc = {}; + fmtdesc.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + fmtdesc.index = 0; + uint32_t best_fmt = 0; + int best_rank = 1 << 30; // large number + + // 注: 当前版本 esp_video 中 YUV422P 实际输出为 YUYV。 +#if defined(CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE) && defined(CONFIG_SOC_PPA_SUPPORTED) + auto get_rank = [](uint32_t fmt) -> int { + switch (fmt) { + case V4L2_PIX_FMT_RGB24: + return 0; + case V4L2_PIX_FMT_RGB565: + return 1; +#ifdef CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + case V4L2_PIX_FMT_YUV420: // 软件 JPEG 编码器不支持 YUV420 格式 + return 2; +#endif // CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + case V4L2_PIX_FMT_GREY: + case V4L2_PIX_FMT_YUV422P: + default: + return 1 << 29; // unsupported + } + }; +#else + auto get_rank = [](uint32_t fmt) -> int { + switch (fmt) { + case V4L2_PIX_FMT_YUV422P: + return 10; + case V4L2_PIX_FMT_RGB565: + return 11; + case V4L2_PIX_FMT_RGB24: + return 12; +#ifdef CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + case V4L2_PIX_FMT_YUV420: + return 13; +#endif // CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER +#ifdef CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + case V4L2_PIX_FMT_JPEG: + return 5; +#endif // CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + case V4L2_PIX_FMT_GREY: + return 20; + default: + return 1 << 29; // unsupported + } + }; +#endif + while (ioctl(video_fd_, VIDIOC_ENUM_FMT, &fmtdesc) == 0) { + ESP_LOGD(TAG, "VIDIOC_ENUM_FMT: pixelformat=0x%08lx, description=%s", fmtdesc.pixelformat, fmtdesc.description); + CAM_PRINT_FOURCC(fmtdesc.pixelformat); + int rank = get_rank(fmtdesc.pixelformat); + if (rank < best_rank) { + best_rank = rank; + best_fmt = fmtdesc.pixelformat; + } + fmtdesc.index++; + } + if (best_rank < (1 << 29)) { + setformat.fmt.pix.pixelformat = best_fmt; + sensor_format_ = best_fmt; + } + + if (!setformat.fmt.pix.pixelformat) { + ESP_LOGE(TAG, "no supported pixel format found"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + + ESP_LOGD(TAG, "selected pixel format: 0x%08lx", setformat.fmt.pix.pixelformat); + + if (ioctl(video_fd_, VIDIOC_S_FMT, &setformat) != 0) { + ESP_LOGE(TAG, "VIDIOC_S_FMT failed, errno=%d(%s)", errno, strerror(errno)); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + frame_.width = setformat.fmt.pix.height; + frame_.height = setformat.fmt.pix.width; +#else + frame_.width = setformat.fmt.pix.width; + frame_.height = setformat.fmt.pix.height; +#endif + + // 申请缓冲并mmap + struct v4l2_requestbuffers req = {}; + req.count = strcmp(video_device_name, ESP_VIDEO_MIPI_CSI_DEVICE_NAME) == 0 ? 2 : 1; + req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + req.memory = V4L2_MEMORY_MMAP; + if (ioctl(video_fd_, VIDIOC_REQBUFS, &req) != 0) { + ESP_LOGE(TAG, "VIDIOC_REQBUFS failed"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + mmap_buffers_.resize(req.count); + for (uint32_t i = 0; i < req.count; i++) { + struct v4l2_buffer buf = {}; + buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + buf.memory = V4L2_MEMORY_MMAP; + buf.index = i; + if (ioctl(video_fd_, VIDIOC_QUERYBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_QUERYBUF failed"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + void* start = mmap(NULL, buf.length, PROT_READ | PROT_WRITE, MAP_SHARED, video_fd_, buf.m.offset); + if (start == MAP_FAILED) { + ESP_LOGE(TAG, "mmap failed"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + mmap_buffers_[i].start = start; + mmap_buffers_[i].length = buf.length; + + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_QBUF failed"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + } + + int type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + if (ioctl(video_fd_, VIDIOC_STREAMON, &type) != 0) { + ESP_LOGE(TAG, "VIDIOC_STREAMON failed"); + close(video_fd_); + video_fd_ = -1; + sensor_format_ = 0; + return; + } + +#ifdef CONFIG_ESP_VIDEO_ENABLE_ISP_VIDEO_DEVICE + // 当启用 ISP 时,ISP 需要一些照片来初始化参数,因此开启后后台拍摄5s照片并丢弃 + xTaskCreate( + [](void* arg) { + Esp32Camera* self = static_cast(arg); + uint16_t capture_count = 0; + TickType_t start = xTaskGetTickCount(); + TickType_t duration = 5000 / portTICK_PERIOD_MS; // 5s + while ((xTaskGetTickCount() - start) < duration) { + struct v4l2_buffer buf = {}; + buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + buf.memory = V4L2_MEMORY_MMAP; + if (ioctl(self->video_fd_, VIDIOC_DQBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_DQBUF failed during init"); + vTaskDelay(10 / portTICK_PERIOD_MS); + continue; + } + if (ioctl(self->video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_QBUF failed during init"); + } + capture_count++; + } + ESP_LOGI(TAG, "Camera init success, captured %d frames in %dms", capture_count, + (xTaskGetTickCount() - start) * portTICK_PERIOD_MS); + self->streaming_on_ = true; + vTaskDelete(NULL); + }, + "CameraInitTask", 4096, this, 5, nullptr); +#else + ESP_LOGI(TAG, "Camera init success"); + streaming_on_ = true; +#endif // CONFIG_ESP_VIDEO_ENABLE_ISP_VIDEO_DEVICE +} + +Esp32Camera::~Esp32Camera() { + if (streaming_on_ && video_fd_ >= 0) { + int type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + ioctl(video_fd_, VIDIOC_STREAMOFF, &type); + } + for (auto& b : mmap_buffers_) { + if (b.start && b.length) { + munmap(b.start, b.length); + } + } + if (video_fd_ >= 0) { + close(video_fd_); + video_fd_ = -1; + } + sensor_format_ = 0; + esp_video_deinit(); +} + +void Esp32Camera::SetExplainUrl(const std::string& url, const std::string& token) { + explain_url_ = url; + explain_token_ = token; +} + +bool Esp32Camera::Capture() { + if (encoder_thread_.joinable()) { + encoder_thread_.join(); + } + + if (!streaming_on_ || video_fd_ < 0) { + return false; + } + + for (int i = 0; i < 3; i++) { + struct v4l2_buffer buf = {}; + buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE; + buf.memory = V4L2_MEMORY_MMAP; + if (ioctl(video_fd_, VIDIOC_DQBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_DQBUF failed"); + return false; + } + if (i == 2) { + // 保存帧副本到PSRAM + if (frame_.data) { + heap_caps_free(frame_.data); + frame_.data = nullptr; + frame_.format = 0; + } + frame_.len = buf.bytesused; + frame_.data = (uint8_t*)heap_caps_malloc(frame_.len, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (!frame_.data) { + ESP_LOGE(TAG, "alloc frame copy failed: need allocate %lu bytes", buf.bytesused); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + ESP_LOGW(TAG, "mmap_buffers_[buf.index].length = %d, sensor_width = %d, sensor_height = %d", + mmap_buffers_[buf.index].length, sensor_width_, sensor_height_); +#else + ESP_LOGW(TAG, "mmap_buffers_[buf.index].length = %d, frame.width = %d, frame.height = %d", + mmap_buffers_[buf.index].length, frame_.width, frame_.height); +#endif // CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + ESP_LOG_BUFFER_HEXDUMP(TAG, mmap_buffers_[buf.index].start, MIN(mmap_buffers_[buf.index].length, 256), + ESP_LOG_DEBUG); + + switch (sensor_format_) { + case V4L2_PIX_FMT_RGB565: + case V4L2_PIX_FMT_RGB24: + case V4L2_PIX_FMT_YUYV: + case V4L2_PIX_FMT_YUV420: + case V4L2_PIX_FMT_GREY: +#ifdef CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + case V4L2_PIX_FMT_JPEG: +#endif // CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP + { + auto src16 = (uint16_t*)mmap_buffers_[buf.index].start; + auto dst16 = (uint16_t*)frame_.data; + size_t count = (size_t)mmap_buffers_[buf.index].length / 2; + for (size_t i = 0; i < count; i++) { + dst16[i] = __builtin_bswap16(src16[i]); + } + } +#else + memcpy(frame_.data, mmap_buffers_[buf.index].start, + MIN(mmap_buffers_[buf.index].length, frame_.len)); +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP + frame_.format = sensor_format_; + break; + case V4L2_PIX_FMT_YUV422P: { + // 这个格式是 422 YUYV,不是 planer + frame_.format = V4L2_PIX_FMT_YUYV; +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP + { + auto src16 = (uint16_t*)mmap_buffers_[buf.index].start; + auto dst16 = (uint16_t*)frame_.data; + size_t count = (size_t)mmap_buffers_[buf.index].length / 2; + for (size_t i = 0; i < count; i++) { + dst16[i] = __builtin_bswap16(src16[i]); + } + } +#else + memcpy(frame_.data, mmap_buffers_[buf.index].start, + MIN(mmap_buffers_[buf.index].length, frame_.len)); +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP + break; + } + case V4L2_PIX_FMT_RGB565X: { + // 大端序的 RGB565 需要转换为小端序 + // 目前 esp_video 的大小端都会返回格式为 RGB565,不会返回格式为 RGB565X,此 case 用于未来版本兼容 + auto src16 = (uint16_t*)mmap_buffers_[buf.index].start; + auto dst16 = (uint16_t*)frame_.data; + size_t pixel_count = (size_t)frame_.width * (size_t)frame_.height; + for (size_t i = 0; i < pixel_count; i++) { + dst16[i] = __builtin_bswap16(src16[i]); + } + frame_.format = V4L2_PIX_FMT_RGB565; + break; + } + default: + ESP_LOGE(TAG, "unsupported sensor format: 0x%08lx", sensor_format_); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE +#ifndef CONFIG_SOC_PPA_SUPPORTED + uint8_t* rotate_dst = + (uint8_t*)heap_caps_aligned_alloc(64, frame_.len, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (rotate_dst == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for rotate image"); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + uint8_t* rotate_src = (uint8_t*)frame_.data; + + esp_imgfx_rotate_cfg_t rotate_cfg = { + .in_res = + { + .width = static_cast(sensor_width_), + .height = static_cast(sensor_height_), + }, + .degree = IMAGE_ROTATION_ANGLE, + }; + switch (frame_.format) { + case V4L2_PIX_FMT_RGB565: + rotate_cfg.in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB565_LE; + break; + case V4L2_PIX_FMT_YUYV: + rotate_cfg.in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB565_LE; + break; + case V4L2_PIX_FMT_GREY: + rotate_cfg.in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_Y; + break; + case V4L2_PIX_FMT_RGB24: + rotate_cfg.in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB888; + break; + default: + ESP_LOGE(TAG, "unsupported sensor format: 0x%08lx", sensor_format_); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + esp_imgfx_rotate_handle_t rotate_handle = nullptr; + esp_imgfx_err_t imgfx_err = esp_imgfx_rotate_open(&rotate_cfg, &rotate_handle); + if (imgfx_err != ESP_IMGFX_ERR_OK || rotate_handle == nullptr) { + ESP_LOGE(TAG, "esp_imgfx_rotate_create failed"); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + + esp_imgfx_data_t rotate_input_data = { + .data = rotate_src, + .data_len = frame_.len, + }; + esp_imgfx_data_t rotate_output_data = { + .data = rotate_dst, + .data_len = frame_.len, + }; + + imgfx_err = esp_imgfx_rotate_process(rotate_handle, &rotate_input_data, &rotate_output_data); + if (imgfx_err != ESP_IMGFX_ERR_OK) { + ESP_LOGE(TAG, "esp_imgfx_rotate_process failed"); + heap_caps_free(rotate_dst); + rotate_dst = nullptr; + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + esp_imgfx_rotate_close(rotate_handle); + rotate_handle = nullptr; + return false; + } + + frame_.data = rotate_dst; + + heap_caps_free(rotate_src); + rotate_src = nullptr; + + esp_imgfx_rotate_close(rotate_handle); + rotate_handle = nullptr; +#else // CONFIG_SOC_PPA_SUPPORTED + uint8_t* rotate_src = nullptr; + + ppa_srm_color_mode_t ppa_color_mode; + switch (frame_.format) { + case V4L2_PIX_FMT_RGB565: + rotate_src = (uint8_t*)frame_.data; + ppa_color_mode = PPA_SRM_COLOR_MODE_RGB565; + break; + case V4L2_PIX_FMT_RGB24: + rotate_src = (uint8_t*)frame_.data; + ppa_color_mode = PPA_SRM_COLOR_MODE_RGB888; + break; + case V4L2_PIX_FMT_YUYV: { + ESP_LOGW(TAG, "YUYV format is not supported for PPA rotation, using software conversion to RGB888"); + rotate_src = (uint8_t*)heap_caps_malloc(frame_.width * frame_.height * 3, + MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (rotate_src == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for rotate image"); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + esp_imgfx_color_convert_cfg_t convert_cfg = { + .in_res = {.width = static_cast(frame_.width), + .height = static_cast(frame_.height)}, + .in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_YUYV, + .out_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB888, + }; + esp_imgfx_color_convert_handle_t convert_handle = nullptr; + esp_imgfx_err_t err = esp_imgfx_color_convert_open(&convert_cfg, &convert_handle); + if (err != ESP_IMGFX_ERR_OK || convert_handle == nullptr) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_open failed"); + heap_caps_free(rotate_src); + rotate_src = nullptr; + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + esp_imgfx_data_t convert_input_data = { + .data = frame_.data, + .data_len = frame_.len, + }; + esp_imgfx_data_t convert_output_data = { + .data = rotate_src, + .data_len = static_cast(frame_.width * frame_.height * 3), + }; + err = esp_imgfx_color_convert_process(convert_handle, &convert_input_data, &convert_output_data); + if (err != ESP_IMGFX_ERR_OK) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_process failed"); + heap_caps_free(rotate_src); + rotate_src = nullptr; + esp_imgfx_color_convert_close(convert_handle); + convert_handle = nullptr; + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + esp_imgfx_color_convert_close(convert_handle); + convert_handle = nullptr; + ppa_color_mode = PPA_SRM_COLOR_MODE_RGB888; + heap_caps_free(frame_.data); + frame_.data = rotate_src; + frame_.len = frame_.width * frame_.height * 3; + break; + } + default: + ESP_LOGE(TAG, "unsupported sensor format for PPA rotation: 0x%08lx", sensor_format_); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + + uint8_t* rotate_dst = (uint8_t*)heap_caps_malloc( + frame_.width * frame_.height * 2, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT | MALLOC_CAP_CACHE_ALIGNED); + if (rotate_dst == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for rotate image"); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + + ppa_client_handle_t ppa_client = nullptr; + ppa_client_config_t client_cfg = { + .oper_type = PPA_OPERATION_SRM, + .max_pending_trans_num = 1, + }; + esp_err_t err = ppa_register_client(&client_cfg, &ppa_client); + if (err != ESP_OK || ppa_client == nullptr) { + ESP_LOGE(TAG, "ppa_register_client failed: %d", (int)err); + heap_caps_free(rotate_dst); + rotate_dst = nullptr; + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + + ppa_srm_rotation_angle_t ppa_angle = IMAGE_ROTATION_ANGLE; + + ppa_srm_oper_config_t srm_cfg = {}; + srm_cfg.in.buffer = (void*)rotate_src; + srm_cfg.in.pic_w = sensor_width_; + srm_cfg.in.pic_h = sensor_height_; + srm_cfg.in.block_w = sensor_width_; + srm_cfg.in.block_h = sensor_height_; + srm_cfg.in.block_offset_x = 0; + srm_cfg.in.block_offset_y = 0; + srm_cfg.in.srm_cm = ppa_color_mode; + + srm_cfg.out.buffer = (void*)rotate_dst; + srm_cfg.out.buffer_size = frame_.len; + srm_cfg.out.pic_w = frame_.width; + srm_cfg.out.pic_h = frame_.height; + srm_cfg.out.block_offset_x = 0; + srm_cfg.out.block_offset_y = 0; + srm_cfg.out.srm_cm = PPA_SRM_COLOR_MODE_RGB565; + + // 等比例缩放 1.0 + srm_cfg.scale_x = 1.0f; + srm_cfg.scale_y = 1.0f; + srm_cfg.rotation_angle = ppa_angle; + srm_cfg.mode = PPA_TRANS_MODE_BLOCKING; + srm_cfg.user_data = nullptr; + + err = ppa_do_scale_rotate_mirror(ppa_client, &srm_cfg); + if (err != ESP_OK) { + ESP_LOGE(TAG, "ppa_do_scale_rotate_mirror failed: %d", (int)err); + heap_caps_free(rotate_dst); + rotate_dst = nullptr; + (void)ppa_unregister_client(ppa_client); + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "Cleanup: VIDIOC_QBUF failed"); + } + return false; + } + + (void)ppa_unregister_client(ppa_client); + + frame_.data = rotate_dst; + frame_.len = frame_.width * frame_.height * 2; + frame_.format = V4L2_PIX_FMT_RGB565; + heap_caps_free(rotate_src); + rotate_src = nullptr; +#endif // CONFIG_SOC_PPA_SUPPORTED +#endif // CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + } + + if (ioctl(video_fd_, VIDIOC_QBUF, &buf) != 0) { + ESP_LOGE(TAG, "VIDIOC_QBUF failed"); + } + } + + // 显示预览图片 + auto display = dynamic_cast(Board::GetInstance().GetDisplay()); + if (display != nullptr) { + if (!frame_.data) { + ESP_LOGE(TAG, "frame.data is null"); + return false; + } + uint16_t w = frame_.width; + uint16_t h = frame_.height; + size_t lvgl_image_size = frame_.len; + size_t stride = ((w * 2) + 3) & ~3; // 4字节对齐 + lv_color_format_t color_format = LV_COLOR_FORMAT_RGB565; + uint8_t* data = nullptr; + + switch (frame_.format) { + // LVGL 显示 YUV 系的图像似乎都有问题,暂时转换为 RGB565 显示 + case V4L2_PIX_FMT_YUYV: + case V4L2_PIX_FMT_YUV420: + case V4L2_PIX_FMT_RGB24: { + color_format = LV_COLOR_FORMAT_RGB565; + data = (uint8_t*)heap_caps_malloc(w * h * 2, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (data == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for preview image"); + return false; + } + esp_imgfx_color_convert_cfg_t convert_cfg = { + .in_res = {.width = static_cast(frame_.width), + .height = static_cast(frame_.height)}, + .in_pixel_fmt = static_cast(frame_.format), + .out_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB565_LE, + .color_space_std = ESP_IMGFX_COLOR_SPACE_STD_BT601, + }; + esp_imgfx_color_convert_handle_t convert_handle = nullptr; + esp_imgfx_err_t err = esp_imgfx_color_convert_open(&convert_cfg, &convert_handle); + if (err != ESP_IMGFX_ERR_OK || convert_handle == nullptr) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_open failed"); + heap_caps_free(data); + data = nullptr; + return false; + } + esp_imgfx_data_t convert_input_data = { + .data = frame_.data, + .data_len = frame_.len, + }; + esp_imgfx_data_t convert_output_data = { + .data = data, + .data_len = static_cast(w * h * 2), + }; + err = esp_imgfx_color_convert_process(convert_handle, &convert_input_data, &convert_output_data); + if (err != ESP_IMGFX_ERR_OK) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_process failed"); + heap_caps_free(data); + data = nullptr; + esp_imgfx_color_convert_close(convert_handle); + convert_handle = nullptr; + return false; + } + esp_imgfx_color_convert_close(convert_handle); + convert_handle = nullptr; + lvgl_image_size = w * h * 2; + break; + } + + case V4L2_PIX_FMT_RGB565: + data = (uint8_t*)heap_caps_malloc(w * h * 2, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (data == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for preview image"); + return false; + } + memcpy(data, frame_.data, frame_.len); + lvgl_image_size = frame_.len; // fallthrough 时兼顾 YUYV 与 RGB565 + break; + +#ifdef CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + case V4L2_PIX_FMT_JPEG: { + uint8_t* out_data = nullptr; // out data is allocated by jpeg_to_image + size_t out_len = 0; + size_t out_width = 0; + size_t out_height = 0; + size_t out_stride = 0; + + esp_err_t ret = + jpeg_to_image(frame_.data, frame_.len, &out_data, &out_len, &out_width, &out_height, &out_stride); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to decode JPEG image: %d (%s)", (int)ret, esp_err_to_name(ret)); + if (out_data) { + heap_caps_free(out_data); + out_data = nullptr; + } + return false; + } + + data = out_data; + w = out_width; + h = out_height; + lvgl_image_size = out_len; + stride = out_stride; + break; + } +#endif + default: + ESP_LOGE(TAG, "unsupported frame format: 0x%08lx", frame_.format); + return false; + } + + auto image = std::make_unique(data, lvgl_image_size, w, h, stride, color_format); + display->SetPreviewImage(std::move(image)); + } + return true; +} + +bool Esp32Camera::SetHMirror(bool enabled) { + if (video_fd_ < 0) + return false; + struct v4l2_ext_controls ctrls = {}; + struct v4l2_ext_control ctrl = {}; + ctrl.id = V4L2_CID_HFLIP; + ctrl.value = enabled ? 1 : 0; + ctrls.ctrl_class = V4L2_CTRL_CLASS_USER; + ctrls.count = 1; + ctrls.controls = &ctrl; + if (ioctl(video_fd_, VIDIOC_S_EXT_CTRLS, &ctrls) != 0) { + ESP_LOGE(TAG, "set HFLIP failed"); + return false; + } + return true; +} + +bool Esp32Camera::SetVFlip(bool enabled) { + if (video_fd_ < 0) + return false; + struct v4l2_ext_controls ctrls = {}; + struct v4l2_ext_control ctrl = {}; + ctrl.id = V4L2_CID_VFLIP; + ctrl.value = enabled ? 1 : 0; + ctrls.ctrl_class = V4L2_CTRL_CLASS_USER; + ctrls.count = 1; + ctrls.controls = &ctrl; + if (ioctl(video_fd_, VIDIOC_S_EXT_CTRLS, &ctrls) != 0) { + ESP_LOGE(TAG, "set VFLIP failed"); + return false; + } + return true; +} + +/** + * @brief 将摄像头捕获的图像发送到远程服务器进行AI分析和解释 + * + * 该函数将当前摄像头缓冲区中的图像编码为JPEG格式,并通过HTTP POST请求 + * 以multipart/form-data的形式发送到指定的解释服务器。服务器将根据提供的 + * 问题对图像进行AI分析并返回结果。 + * + * 实现特点: + * - 使用独立线程编码JPEG,与主线程分离 + * - 采用分块传输编码(chunked transfer encoding)优化内存使用 + * - 通过队列机制实现编码线程和发送线程的数据同步 + * - 支持设备ID、客户端ID和认证令牌的HTTP头部配置 + * + * @param question 要向AI提出的关于图像的问题,将作为表单字段发送 + * @return std::string 服务器返回的JSON格式响应字符串 + * 成功时包含AI分析结果,失败时包含错误信息 + * 格式示例:{"success": true, "result": "分析结果"} + * {"success": false, "message": "错误信息"} + * + * @note 调用此函数前必须先调用SetExplainUrl()设置服务器URL + * @note 函数会等待之前的编码线程完成后再开始新的处理 + * @warning 如果摄像头缓冲区为空或网络连接失败,将返回错误信息 + */ +std::string Esp32Camera::Explain(const std::string& question) { + if (explain_url_.empty()) { + throw std::runtime_error("Image explain URL or token is not set"); + } + + // 创建局部的 JPEG 队列, 40 entries is about to store 512 * 40 = 20480 bytes of JPEG data + QueueHandle_t jpeg_queue = xQueueCreate(40, sizeof(JpegChunk)); + if (jpeg_queue == nullptr) { + ESP_LOGE(TAG, "Failed to create JPEG queue"); + throw std::runtime_error("Failed to create JPEG queue"); + } + + // We spawn a thread to encode the image to JPEG using optimized encoder (cost about 500ms and 8KB SRAM) + encoder_thread_ = std::thread([this, jpeg_queue]() { + uint16_t w = frame_.width ? frame_.width : 320; + uint16_t h = frame_.height ? frame_.height : 240; + v4l2_pix_fmt_t enc_fmt = frame_.format; + bool ok = image_to_jpeg_cb( + frame_.data, frame_.len, w, h, enc_fmt, 80, + [](void* arg, size_t index, const void* data, size_t len) -> size_t { + auto jpeg_queue = static_cast(arg); + JpegChunk chunk = {.data = nullptr, .len = len}; + if (index == 0 && data != nullptr && len > 0) { + chunk.data = (uint8_t*)heap_caps_aligned_alloc(16, len, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (chunk.data == nullptr) { + ESP_LOGE(TAG, "Failed to allocate %zu bytes for JPEG chunk", len); + chunk.len = 0; + } else { + memcpy(chunk.data, data, len); + } + } else { + chunk.len = 0; // Sentinel or error + } + xQueueSend(jpeg_queue, &chunk, portMAX_DELAY); + return len; + }, + jpeg_queue); + + if (!ok) { + JpegChunk chunk = {.data = nullptr, .len = 0}; + xQueueSend(jpeg_queue, &chunk, portMAX_DELAY); + } + }); + + auto network = Board::GetInstance().GetNetwork(); + auto http = network->CreateHttp(3); + // 构造multipart/form-data请求体 + std::string boundary = "----ESP32_CAMERA_BOUNDARY"; + + // 配置HTTP客户端,使用分块传输编码 + http->SetHeader("Device-Id", SystemInfo::GetMacAddress().c_str()); + http->SetHeader("Client-Id", Board::GetInstance().GetUuid().c_str()); + if (!explain_token_.empty()) { + http->SetHeader("Authorization", "Bearer " + explain_token_); + } + http->SetHeader("Content-Type", "multipart/form-data; boundary=" + boundary); + http->SetHeader("Transfer-Encoding", "chunked"); + if (!http->Open("POST", explain_url_)) { + ESP_LOGE(TAG, "Failed to connect to explain URL"); + // Clear the queue + encoder_thread_.join(); + JpegChunk chunk; + while (xQueueReceive(jpeg_queue, &chunk, portMAX_DELAY) == pdPASS) { + if (chunk.data != nullptr) { + heap_caps_free(chunk.data); + } else { + break; + } + } + vQueueDelete(jpeg_queue); + throw std::runtime_error("Failed to connect to explain URL"); + } + + { + // 第一块:question字段 + std::string question_field; + question_field += "--" + boundary + "\r\n"; + question_field += "Content-Disposition: form-data; name=\"question\"\r\n"; + question_field += "\r\n"; + question_field += question + "\r\n"; + http->Write(question_field.c_str(), question_field.size()); + } + { + // 第二块:文件字段头部 + std::string file_header; + file_header += "--" + boundary + "\r\n"; + file_header += "Content-Disposition: form-data; name=\"file\"; filename=\"camera.jpg\"\r\n"; + file_header += "Content-Type: image/jpeg\r\n"; + file_header += "\r\n"; + http->Write(file_header.c_str(), file_header.size()); + } + + // 第三块:JPEG数据 + size_t total_sent = 0; + bool saw_terminator = false; + while (true) { + JpegChunk chunk; + if (xQueueReceive(jpeg_queue, &chunk, portMAX_DELAY) != pdPASS) { + ESP_LOGE(TAG, "Failed to receive JPEG chunk"); + break; + } + if (chunk.data == nullptr) { + saw_terminator = true; + break; // The last chunk + } + http->Write((const char*)chunk.data, chunk.len); + total_sent += chunk.len; + heap_caps_free(chunk.data); + } + // Wait for the encoder thread to finish + encoder_thread_.join(); + // 清理队列 + vQueueDelete(jpeg_queue); + + if (!saw_terminator || total_sent == 0) { + ESP_LOGE(TAG, "JPEG encoder failed or produced empty output"); + throw std::runtime_error("Failed to encode image to JPEG"); + } + + { + // 第四块:multipart尾部 + std::string multipart_footer; + multipart_footer += "\r\n--" + boundary + "--\r\n"; + http->Write(multipart_footer.c_str(), multipart_footer.size()); + } + // 结束块 + http->Write("", 0); + + if (http->GetStatusCode() != 200) { + ESP_LOGE(TAG, "Failed to upload photo, status code: %d", http->GetStatusCode()); + throw std::runtime_error("Failed to upload photo"); + } + + std::string result = http->ReadAll(); + http->Close(); + + // Get remain task stack size + size_t remain_stack_size = uxTaskGetStackHighWaterMark(nullptr); + ESP_LOGI(TAG, "Explain image size=%d bytes, compressed size=%d, remain stack size=%d, question=%s\n%s", + (int)frame_.len, (int)total_sent, (int)remain_stack_size, question.c_str(), result.c_str()); + return result; +} diff --git a/main/boards/common/esp32_camera.h b/main/boards/common/esp32_camera.h new file mode 100644 index 0000000..84366ac --- /dev/null +++ b/main/boards/common/esp32_camera.h @@ -0,0 +1,56 @@ +#pragma once +#include "sdkconfig.h" + +#ifndef CONFIG_IDF_TARGET_ESP32 +#include +#include +#include +#include + +#include +#include + +#include "camera.h" +#include "jpg/image_to_jpeg.h" +#include "esp_video_init.h" + +struct JpegChunk { + uint8_t* data; + size_t len; +}; + +class Esp32Camera : public Camera { +private: + struct FrameBuffer { + uint8_t *data = nullptr; + size_t len = 0; + uint16_t width = 0; + uint16_t height = 0; + v4l2_pix_fmt_t format = 0; + } frame_; + v4l2_pix_fmt_t sensor_format_ = 0; +#ifdef CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + uint16_t sensor_width_ = 0; + uint16_t sensor_height_ = 0; +#endif // CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE + int video_fd_ = -1; + bool streaming_on_ = false; + struct MmapBuffer { void *start = nullptr; size_t length = 0; }; + std::vector mmap_buffers_; + std::string explain_url_; + std::string explain_token_; + std::thread encoder_thread_; + +public: + Esp32Camera(const esp_video_init_config_t& config); + ~Esp32Camera(); + + virtual void SetExplainUrl(const std::string& url, const std::string& token); + virtual bool Capture(); + // 翻转控制函数 + virtual bool SetHMirror(bool enabled) override; + virtual bool SetVFlip(bool enabled) override; + virtual std::string Explain(const std::string& question); +}; + +#endif // ndef CONFIG_IDF_TARGET_ESP32 \ No newline at end of file diff --git a/main/boards/common/i2c_device.cc b/main/boards/common/i2c_device.cc new file mode 100644 index 0000000..835997d --- /dev/null +++ b/main/boards/common/i2c_device.cc @@ -0,0 +1,35 @@ +#include "i2c_device.h" + +#include + +#define TAG "I2cDevice" + + +I2cDevice::I2cDevice(i2c_master_bus_handle_t i2c_bus, uint8_t addr) { + i2c_device_config_t i2c_device_cfg = { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = addr, + .scl_speed_hz = 400 * 1000, + .scl_wait_us = 0, + .flags = { + .disable_ack_check = 0, + }, + }; + ESP_ERROR_CHECK(i2c_master_bus_add_device(i2c_bus, &i2c_device_cfg, &i2c_device_)); + assert(i2c_device_ != NULL); +} + +void I2cDevice::WriteReg(uint8_t reg, uint8_t value) { + uint8_t buffer[2] = {reg, value}; + ESP_ERROR_CHECK(i2c_master_transmit(i2c_device_, buffer, 2, 100)); +} + +uint8_t I2cDevice::ReadReg(uint8_t reg) { + uint8_t buffer[1]; + ESP_ERROR_CHECK(i2c_master_transmit_receive(i2c_device_, ®, 1, buffer, 1, 100)); + return buffer[0]; +} + +void I2cDevice::ReadRegs(uint8_t reg, uint8_t* buffer, size_t length) { + ESP_ERROR_CHECK(i2c_master_transmit_receive(i2c_device_, ®, 1, buffer, length, 100)); +} \ No newline at end of file diff --git a/main/boards/common/i2c_device.h b/main/boards/common/i2c_device.h new file mode 100644 index 0000000..7bc917b --- /dev/null +++ b/main/boards/common/i2c_device.h @@ -0,0 +1,18 @@ +#ifndef I2C_DEVICE_H +#define I2C_DEVICE_H + +#include + +class I2cDevice { +public: + I2cDevice(i2c_master_bus_handle_t i2c_bus, uint8_t addr); + +protected: + i2c_master_dev_handle_t i2c_device_; + + void WriteReg(uint8_t reg, uint8_t value); + uint8_t ReadReg(uint8_t reg); + void ReadRegs(uint8_t reg, uint8_t* buffer, size_t length); +}; + +#endif // I2C_DEVICE_H diff --git a/main/boards/common/knob.cc b/main/boards/common/knob.cc new file mode 100644 index 0000000..350fda2 --- /dev/null +++ b/main/boards/common/knob.cc @@ -0,0 +1,52 @@ +#include "knob.h" + +static const char* TAG = "Knob"; + +Knob::Knob(gpio_num_t pin_a, gpio_num_t pin_b) { + knob_config_t config = { + .default_direction = 0, + .gpio_encoder_a = static_cast(pin_a), + .gpio_encoder_b = static_cast(pin_b), + }; + + esp_err_t err = ESP_OK; + knob_handle_ = iot_knob_create(&config); + if (knob_handle_ == NULL) { + ESP_LOGE(TAG, "Failed to create knob instance"); + return; + } + + err = iot_knob_register_cb(knob_handle_, KNOB_LEFT, knob_callback, this); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to register left callback: %s", esp_err_to_name(err)); + return; + } + + err = iot_knob_register_cb(knob_handle_, KNOB_RIGHT, knob_callback, this); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to register right callback: %s", esp_err_to_name(err)); + return; + } + + ESP_LOGI(TAG, "Knob initialized with pins A:%d B:%d", pin_a, pin_b); +} + +Knob::~Knob() { + if (knob_handle_ != NULL) { + iot_knob_delete(knob_handle_); + knob_handle_ = NULL; + } +} + +void Knob::OnRotate(std::function callback) { + on_rotate_ = callback; +} + +void Knob::knob_callback(void* arg, void* data) { + Knob* knob = static_cast(data); + knob_event_t event = iot_knob_get_event(arg); + + if (knob->on_rotate_) { + knob->on_rotate_(event == KNOB_RIGHT); + } +} \ No newline at end of file diff --git a/main/boards/common/knob.h b/main/boards/common/knob.h new file mode 100644 index 0000000..efea5f5 --- /dev/null +++ b/main/boards/common/knob.h @@ -0,0 +1,25 @@ +#ifndef KNOB_H_ +#define KNOB_H_ + +#include +#include +#include +#include + +class Knob { +public: + Knob(gpio_num_t pin_a, gpio_num_t pin_b); + ~Knob(); + + void OnRotate(std::function callback); + +private: + static void knob_callback(void* arg, void* data); + + knob_handle_t knob_handle_; + gpio_num_t pin_a_; + gpio_num_t pin_b_; + std::function on_rotate_; +}; + +#endif // KNOB_H_ \ No newline at end of file diff --git a/main/boards/common/lamp_controller.h b/main/boards/common/lamp_controller.h new file mode 100644 index 0000000..1ed142c --- /dev/null +++ b/main/boards/common/lamp_controller.h @@ -0,0 +1,44 @@ +#ifndef __LAMP_CONTROLLER_H__ +#define __LAMP_CONTROLLER_H__ + +#include "mcp_server.h" + + +class LampController { +private: + bool power_ = false; + gpio_num_t gpio_num_; + +public: + LampController(gpio_num_t gpio_num) : gpio_num_(gpio_num) { + gpio_config_t config = { + .pin_bit_mask = (1ULL << gpio_num_), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + ESP_ERROR_CHECK(gpio_config(&config)); + gpio_set_level(gpio_num_, 0); + + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.lamp.get_state", "Get the power state of the lamp", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return power_ ? "{\"power\": true}" : "{\"power\": false}"; + }); + + mcp_server.AddTool("self.lamp.turn_on", "Turn on the lamp", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + power_ = true; + gpio_set_level(gpio_num_, 1); + return true; + }); + + mcp_server.AddTool("self.lamp.turn_off", "Turn off the lamp", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + power_ = false; + gpio_set_level(gpio_num_, 0); + return true; + }); + } +}; + + +#endif // __LAMP_CONTROLLER_H__ diff --git a/main/boards/common/ml307_board.cc b/main/boards/common/ml307_board.cc new file mode 100644 index 0000000..63cf09c --- /dev/null +++ b/main/boards/common/ml307_board.cc @@ -0,0 +1,197 @@ +#include "ml307_board.h" + +#include "application.h" +#include "display.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include + +static const char *TAG = "Ml307Board"; + +Ml307Board::Ml307Board(gpio_num_t tx_pin, gpio_num_t rx_pin, gpio_num_t dtr_pin) : tx_pin_(tx_pin), rx_pin_(rx_pin), dtr_pin_(dtr_pin) { +} + +std::string Ml307Board::GetBoardType() { + return "ml307"; +} + +void Ml307Board::StartNetwork() { + auto& application = Application::GetInstance(); + auto display = Board::GetInstance().GetDisplay(); + display->SetStatus(Lang::Strings::DETECTING_MODULE); + + while (true) { + modem_ = AtModem::Detect(tx_pin_, rx_pin_, dtr_pin_, 921600); + if (modem_ != nullptr) { + break; + } + vTaskDelay(pdMS_TO_TICKS(1000)); + } + + modem_->OnNetworkStateChanged([this, &application](bool network_ready) { + if (network_ready) { + ESP_LOGI(TAG, "Network is ready"); + } else { + ESP_LOGE(TAG, "Network is down"); + auto device_state = application.GetDeviceState(); + if (device_state == kDeviceStateListening || device_state == kDeviceStateSpeaking) { + application.Schedule([this, &application]() { + application.SetDeviceState(kDeviceStateIdle); + }); + } + } + }); + + // Wait for network ready + display->SetStatus(Lang::Strings::REGISTERING_NETWORK); + while (true) { + auto result = modem_->WaitForNetworkReady(); + if (result == NetworkStatus::ErrorInsertPin) { + application.Alert(Lang::Strings::ERROR, Lang::Strings::PIN_ERROR, "triangle_exclamation", Lang::Sounds::OGG_ERR_PIN); + } else if (result == NetworkStatus::ErrorRegistrationDenied) { + application.Alert(Lang::Strings::ERROR, Lang::Strings::REG_ERROR, "triangle_exclamation", Lang::Sounds::OGG_ERR_REG); + } else { + break; + } + vTaskDelay(pdMS_TO_TICKS(10000)); + } + + // Print the ML307 modem information + std::string module_revision = modem_->GetModuleRevision(); + std::string imei = modem_->GetImei(); + std::string iccid = modem_->GetIccid(); + ESP_LOGI(TAG, "ML307 Revision: %s", module_revision.c_str()); + ESP_LOGI(TAG, "ML307 IMEI: %s", imei.c_str()); + ESP_LOGI(TAG, "ML307 ICCID: %s", iccid.c_str()); +} + +NetworkInterface* Ml307Board::GetNetwork() { + return modem_.get(); +} + +const char* Ml307Board::GetNetworkStateIcon() { + if (modem_ == nullptr || !modem_->network_ready()) { + return FONT_AWESOME_SIGNAL_OFF; + } + int csq = modem_->GetCsq(); + if (csq == -1) { + return FONT_AWESOME_SIGNAL_OFF; + } else if (csq >= 0 && csq <= 14) { + return FONT_AWESOME_SIGNAL_WEAK; + } else if (csq >= 15 && csq <= 19) { + return FONT_AWESOME_SIGNAL_FAIR; + } else if (csq >= 20 && csq <= 24) { + return FONT_AWESOME_SIGNAL_GOOD; + } else if (csq >= 25 && csq <= 31) { + return FONT_AWESOME_SIGNAL_STRONG; + } + + ESP_LOGW(TAG, "Invalid CSQ: %d", csq); + return FONT_AWESOME_SIGNAL_OFF; +} + +std::string Ml307Board::GetBoardJson() { + // Set the board type for OTA + std::string board_json = std::string("{\"type\":\"" BOARD_TYPE "\","); + board_json += "\"name\":\"" BOARD_NAME "\","; + board_json += "\"revision\":\"" + modem_->GetModuleRevision() + "\","; + board_json += "\"carrier\":\"" + modem_->GetCarrierName() + "\","; + board_json += "\"csq\":\"" + std::to_string(modem_->GetCsq()) + "\","; + board_json += "\"imei\":\"" + modem_->GetImei() + "\","; + board_json += "\"iccid\":\"" + modem_->GetIccid() + "\","; + board_json += "\"cereg\":" + modem_->GetRegistrationState().ToString() + "}"; + return board_json; +} + +void Ml307Board::SetPowerSaveMode(bool enabled) { + // TODO: Implement power save mode for ML307 +} + +std::string Ml307Board::GetDeviceStatusJson() { + /* + * 返回设备状态JSON + * + * 返回的JSON结构如下: + * { + * "audio_speaker": { + * "volume": 70 + * }, + * "screen": { + * "brightness": 100, + * "theme": "light" + * }, + * "battery": { + * "level": 50, + * "charging": true + * }, + * "network": { + * "type": "cellular", + * "carrier": "CHINA MOBILE", + * "csq": 10 + * } + * } + */ + auto& board = Board::GetInstance(); + auto root = cJSON_CreateObject(); + + // Audio speaker + auto audio_speaker = cJSON_CreateObject(); + auto audio_codec = board.GetAudioCodec(); + if (audio_codec) { + cJSON_AddNumberToObject(audio_speaker, "volume", audio_codec->output_volume()); + } + cJSON_AddItemToObject(root, "audio_speaker", audio_speaker); + + // Screen brightness + auto backlight = board.GetBacklight(); + auto screen = cJSON_CreateObject(); + if (backlight) { + cJSON_AddNumberToObject(screen, "brightness", backlight->brightness()); + } + auto display = board.GetDisplay(); + if (display && display->height() > 64) { // For LCD display only + auto theme = display->GetTheme(); + if (theme != nullptr) { + cJSON_AddStringToObject(screen, "theme", theme->name().c_str()); + } + } + cJSON_AddItemToObject(root, "screen", screen); + + // Battery + int battery_level = 0; + bool charging = false; + bool discharging = false; + if (board.GetBatteryLevel(battery_level, charging, discharging)) { + cJSON* battery = cJSON_CreateObject(); + cJSON_AddNumberToObject(battery, "level", battery_level); + cJSON_AddBoolToObject(battery, "charging", charging); + cJSON_AddItemToObject(root, "battery", battery); + } + + // Network + auto network = cJSON_CreateObject(); + cJSON_AddStringToObject(network, "type", "cellular"); + cJSON_AddStringToObject(network, "carrier", modem_->GetCarrierName().c_str()); + int csq = modem_->GetCsq(); + if (csq == -1) { + cJSON_AddStringToObject(network, "signal", "unknown"); + } else if (csq >= 0 && csq <= 14) { + cJSON_AddStringToObject(network, "signal", "very weak"); + } else if (csq >= 15 && csq <= 19) { + cJSON_AddStringToObject(network, "signal", "weak"); + } else if (csq >= 20 && csq <= 24) { + cJSON_AddStringToObject(network, "signal", "medium"); + } else if (csq >= 25 && csq <= 31) { + cJSON_AddStringToObject(network, "signal", "strong"); + } + cJSON_AddItemToObject(root, "network", network); + + auto json_str = cJSON_PrintUnformatted(root); + std::string json(json_str); + cJSON_free(json_str); + cJSON_Delete(root); + return json; +} diff --git a/main/boards/common/ml307_board.h b/main/boards/common/ml307_board.h new file mode 100644 index 0000000..22dddf9 --- /dev/null +++ b/main/boards/common/ml307_board.h @@ -0,0 +1,29 @@ +#ifndef ML307_BOARD_H +#define ML307_BOARD_H + +#include +#include +#include "board.h" + + +class Ml307Board : public Board { +protected: + std::unique_ptr modem_; + gpio_num_t tx_pin_; + gpio_num_t rx_pin_; + gpio_num_t dtr_pin_; + + virtual std::string GetBoardJson() override; + +public: + Ml307Board(gpio_num_t tx_pin, gpio_num_t rx_pin, gpio_num_t dtr_pin = GPIO_NUM_NC); + virtual std::string GetBoardType() override; + virtual void StartNetwork() override; + virtual NetworkInterface* GetNetwork() override; + virtual const char* GetNetworkStateIcon() override; + virtual void SetPowerSaveMode(bool enabled) override; + virtual AudioCodec* GetAudioCodec() override { return nullptr; } + virtual std::string GetDeviceStatusJson() override; +}; + +#endif // ML307_BOARD_H diff --git a/main/boards/common/power_save_timer.cc b/main/boards/common/power_save_timer.cc new file mode 100644 index 0000000..522e64c --- /dev/null +++ b/main/boards/common/power_save_timer.cc @@ -0,0 +1,132 @@ +#include "power_save_timer.h" +#include "application.h" +#include "settings.h" + +#include + +#define TAG "PowerSaveTimer" + + +PowerSaveTimer::PowerSaveTimer(int cpu_max_freq, int seconds_to_sleep, int seconds_to_shutdown) + : cpu_max_freq_(cpu_max_freq), seconds_to_sleep_(seconds_to_sleep), seconds_to_shutdown_(seconds_to_shutdown) { + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + auto self = static_cast(arg); + self->PowerSaveCheck(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "power_save_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &power_save_timer_)); +} + +PowerSaveTimer::~PowerSaveTimer() { + esp_timer_stop(power_save_timer_); + esp_timer_delete(power_save_timer_); +} + +void PowerSaveTimer::SetEnabled(bool enabled) { + if (enabled && !enabled_) { + Settings settings("wifi", false); + if (!settings.GetBool("sleep_mode", true)) { + ESP_LOGI(TAG, "Power save timer is disabled by settings"); + return; + } + + ticks_ = 0; + enabled_ = enabled; + ESP_ERROR_CHECK(esp_timer_start_periodic(power_save_timer_, 1000000)); + ESP_LOGI(TAG, "Power save timer enabled"); + } else if (!enabled && enabled_) { + ESP_ERROR_CHECK(esp_timer_stop(power_save_timer_)); + enabled_ = enabled; + WakeUp(); + ESP_LOGI(TAG, "Power save timer disabled"); + } +} + +void PowerSaveTimer::OnEnterSleepMode(std::function callback) { + on_enter_sleep_mode_ = callback; +} + +void PowerSaveTimer::OnExitSleepMode(std::function callback) { + on_exit_sleep_mode_ = callback; +} + +void PowerSaveTimer::OnShutdownRequest(std::function callback) { + on_shutdown_request_ = callback; +} + +void PowerSaveTimer::PowerSaveCheck() { + auto& app = Application::GetInstance(); + if (!in_sleep_mode_ && !app.CanEnterSleepMode()) { + ticks_ = 0; + return; + } + + ticks_++; + if (seconds_to_sleep_ != -1 && ticks_ >= seconds_to_sleep_) { + if (!in_sleep_mode_) { + ESP_LOGI(TAG, "Enabling power save mode"); + in_sleep_mode_ = true; + if (on_enter_sleep_mode_) { + on_enter_sleep_mode_(); + } + + if (cpu_max_freq_ != -1) { + // Disable wake word detection + auto& audio_service = app.GetAudioService(); + is_wake_word_running_ = audio_service.IsWakeWordRunning(); + if (is_wake_word_running_) { + audio_service.EnableWakeWordDetection(false); + vTaskDelay(pdMS_TO_TICKS(100)); + } + // Disable audio input + auto codec = Board::GetInstance().GetAudioCodec(); + if (codec) { + codec->EnableInput(false); + } + + esp_pm_config_t pm_config = { + .max_freq_mhz = cpu_max_freq_, + .min_freq_mhz = 40, + .light_sleep_enable = true, + }; + esp_pm_configure(&pm_config); + } + } + } + if (seconds_to_shutdown_ != -1 && ticks_ >= seconds_to_shutdown_ && on_shutdown_request_) { + on_shutdown_request_(); + } +} + +void PowerSaveTimer::WakeUp() { + ticks_ = 0; + if (in_sleep_mode_) { + ESP_LOGI(TAG, "Exiting power save mode"); + in_sleep_mode_ = false; + + if (cpu_max_freq_ != -1) { + esp_pm_config_t pm_config = { + .max_freq_mhz = cpu_max_freq_, + .min_freq_mhz = cpu_max_freq_, + .light_sleep_enable = false, + }; + esp_pm_configure(&pm_config); + + // Enable wake word detection + auto& app = Application::GetInstance(); + auto& audio_service = app.GetAudioService(); + if (is_wake_word_running_) { + audio_service.EnableWakeWordDetection(true); + } + } + + if (on_exit_sleep_mode_) { + on_exit_sleep_mode_(); + } + } +} diff --git a/main/boards/common/power_save_timer.h b/main/boards/common/power_save_timer.h new file mode 100644 index 0000000..4c95671 --- /dev/null +++ b/main/boards/common/power_save_timer.h @@ -0,0 +1,34 @@ +#pragma once + +#include + +#include +#include + +class PowerSaveTimer { +public: + PowerSaveTimer(int cpu_max_freq, int seconds_to_sleep = 20, int seconds_to_shutdown = -1); + ~PowerSaveTimer(); + + void SetEnabled(bool enabled); + void OnEnterSleepMode(std::function callback); + void OnExitSleepMode(std::function callback); + void OnShutdownRequest(std::function callback); + void WakeUp(); + +private: + void PowerSaveCheck(); + + esp_timer_handle_t power_save_timer_ = nullptr; + bool enabled_ = false; + bool in_sleep_mode_ = false; + bool is_wake_word_running_ = false; + int ticks_ = 0; + int cpu_max_freq_; + int seconds_to_sleep_; + int seconds_to_shutdown_; + + std::function on_enter_sleep_mode_; + std::function on_exit_sleep_mode_; + std::function on_shutdown_request_; +}; diff --git a/main/boards/common/press_to_talk_mcp_tool.cc b/main/boards/common/press_to_talk_mcp_tool.cc new file mode 100644 index 0000000..d6b0bc9 --- /dev/null +++ b/main/boards/common/press_to_talk_mcp_tool.cc @@ -0,0 +1,57 @@ +#include "press_to_talk_mcp_tool.h" +#include + +static const char* TAG = "PressToTalkMcpTool"; + +PressToTalkMcpTool::PressToTalkMcpTool() + : press_to_talk_enabled_(false) { +} + +void PressToTalkMcpTool::Initialize() { + // 从设置中读取当前状态 + Settings settings("vendor"); + press_to_talk_enabled_ = settings.GetInt("press_to_talk", 0) != 0; + + // 注册MCP工具 + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.set_press_to_talk", + "Switch between press to talk mode (长按说话) and click to talk mode (单击说话).\n" + "The mode can be `press_to_talk` or `click_to_talk`.", + PropertyList({ + Property("mode", kPropertyTypeString) + }), + [this](const PropertyList& properties) -> ReturnValue { + return HandleSetPressToTalk(properties); + }); + + ESP_LOGI(TAG, "PressToTalkMcpTool initialized, current mode: %s", + press_to_talk_enabled_ ? "press_to_talk" : "click_to_talk"); +} + +bool PressToTalkMcpTool::IsPressToTalkEnabled() const { + return press_to_talk_enabled_; +} + +ReturnValue PressToTalkMcpTool::HandleSetPressToTalk(const PropertyList& properties) { + auto mode = properties["mode"].value(); + + if (mode == "press_to_talk") { + SetPressToTalkEnabled(true); + ESP_LOGI(TAG, "Switched to press to talk mode"); + return true; + } else if (mode == "click_to_talk") { + SetPressToTalkEnabled(false); + ESP_LOGI(TAG, "Switched to click to talk mode"); + return true; + } + + throw std::runtime_error("Invalid mode: " + mode); +} + +void PressToTalkMcpTool::SetPressToTalkEnabled(bool enabled) { + press_to_talk_enabled_ = enabled; + + Settings settings("vendor", true); + settings.SetInt("press_to_talk", enabled ? 1 : 0); + ESP_LOGI(TAG, "Press to talk enabled: %d", enabled); +} \ No newline at end of file diff --git a/main/boards/common/press_to_talk_mcp_tool.h b/main/boards/common/press_to_talk_mcp_tool.h new file mode 100644 index 0000000..3231a28 --- /dev/null +++ b/main/boards/common/press_to_talk_mcp_tool.h @@ -0,0 +1,29 @@ +#ifndef PRESS_TO_TALK_MCP_TOOL_H +#define PRESS_TO_TALK_MCP_TOOL_H + +#include "mcp_server.h" +#include "settings.h" + +// 可复用的按键说话模式MCP工具类 +class PressToTalkMcpTool { +private: + bool press_to_talk_enabled_; + +public: + PressToTalkMcpTool(); + + // 初始化工具,注册到MCP服务器 + void Initialize(); + + // 获取当前按键说话模式状态 + bool IsPressToTalkEnabled() const; + +private: + // MCP工具的回调函数 + ReturnValue HandleSetPressToTalk(const PropertyList& properties); + + // 内部方法:设置press to talk状态并保存到设置 + void SetPressToTalkEnabled(bool enabled); +}; + +#endif // PRESS_TO_TALK_MCP_TOOL_H \ No newline at end of file diff --git a/main/boards/common/sleep_timer.cc b/main/boards/common/sleep_timer.cc new file mode 100644 index 0000000..3490f6c --- /dev/null +++ b/main/boards/common/sleep_timer.cc @@ -0,0 +1,133 @@ +#include "sleep_timer.h" +#include "application.h" +#include "board.h" +#include "display.h" +#include "settings.h" + +#include +#include +#include + +#define TAG "SleepTimer" + + +SleepTimer::SleepTimer(int seconds_to_light_sleep, int seconds_to_deep_sleep) + : seconds_to_light_sleep_(seconds_to_light_sleep), seconds_to_deep_sleep_(seconds_to_deep_sleep) { + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + auto self = static_cast(arg); + self->CheckTimer(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "sleep_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &sleep_timer_)); +} + +SleepTimer::~SleepTimer() { + esp_timer_stop(sleep_timer_); + esp_timer_delete(sleep_timer_); +} + +void SleepTimer::SetEnabled(bool enabled) { + if (enabled && !enabled_) { + Settings settings("wifi", false); + if (!settings.GetBool("sleep_mode", true)) { + ESP_LOGI(TAG, "Power save timer is disabled by settings"); + return; + } + + ticks_ = 0; + enabled_ = enabled; + ESP_ERROR_CHECK(esp_timer_start_periodic(sleep_timer_, 1000000)); + ESP_LOGI(TAG, "Sleep timer enabled"); + } else if (!enabled && enabled_) { + ESP_ERROR_CHECK(esp_timer_stop(sleep_timer_)); + enabled_ = enabled; + WakeUp(); + ESP_LOGI(TAG, "Sleep timer disabled"); + } +} + +void SleepTimer::OnEnterLightSleepMode(std::function callback) { + on_enter_light_sleep_mode_ = callback; +} + +void SleepTimer::OnExitLightSleepMode(std::function callback) { + on_exit_light_sleep_mode_ = callback; +} + +void SleepTimer::OnEnterDeepSleepMode(std::function callback) { + on_enter_deep_sleep_mode_ = callback; +} + +void SleepTimer::CheckTimer() { + auto& app = Application::GetInstance(); + if (!app.CanEnterSleepMode()) { + ticks_ = 0; + return; + } + + ticks_++; + if (seconds_to_light_sleep_ != -1 && ticks_ >= seconds_to_light_sleep_) { + if (!in_light_sleep_mode_) { + in_light_sleep_mode_ = true; + if (on_enter_light_sleep_mode_) { + on_enter_light_sleep_mode_(); + } + + auto& audio_service = app.GetAudioService(); + bool is_wake_word_running = audio_service.IsWakeWordRunning(); + if (is_wake_word_running) { + audio_service.EnableWakeWordDetection(false); + vTaskDelay(pdMS_TO_TICKS(100)); + } + + app.Schedule([this, &app]() { + while (in_light_sleep_mode_) { + auto& board = Board::GetInstance(); + board.GetDisplay()->UpdateStatusBar(true); + lv_refr_now(nullptr); + lvgl_port_stop(); + + // 配置timer唤醒源(30秒后自动唤醒) + esp_sleep_enable_timer_wakeup(30 * 1000000); + + // 进入light sleep模式 + esp_light_sleep_start(); + lvgl_port_resume(); + + auto wakeup_reason = esp_sleep_get_wakeup_cause(); + ESP_LOGI(TAG, "Wake up from light sleep, wakeup_reason: %d", wakeup_reason); + if (wakeup_reason != ESP_SLEEP_WAKEUP_TIMER) { + break; + } + } + WakeUp(); + }); + + if (is_wake_word_running) { + audio_service.EnableWakeWordDetection(true); + } + } + } + if (seconds_to_deep_sleep_ != -1 && ticks_ >= seconds_to_deep_sleep_) { + if (on_enter_deep_sleep_mode_) { + on_enter_deep_sleep_mode_(); + } + + esp_deep_sleep_start(); + } +} + +void SleepTimer::WakeUp() { + ticks_ = 0; + if (in_light_sleep_mode_) { + in_light_sleep_mode_ = false; + if (on_exit_light_sleep_mode_) { + on_exit_light_sleep_mode_(); + } + } +} diff --git a/main/boards/common/sleep_timer.h b/main/boards/common/sleep_timer.h new file mode 100644 index 0000000..159e220 --- /dev/null +++ b/main/boards/common/sleep_timer.h @@ -0,0 +1,32 @@ +#pragma once + +#include + +#include +#include + +class SleepTimer { +public: + SleepTimer(int seconds_to_light_sleep = 20, int seconds_to_deep_sleep = -1); + ~SleepTimer(); + + void SetEnabled(bool enabled); + void OnEnterLightSleepMode(std::function callback); + void OnExitLightSleepMode(std::function callback); + void OnEnterDeepSleepMode(std::function callback); + void WakeUp(); + +private: + void CheckTimer(); + + esp_timer_handle_t sleep_timer_ = nullptr; + bool enabled_ = false; + int ticks_ = 0; + int seconds_to_light_sleep_; + int seconds_to_deep_sleep_; + bool in_light_sleep_mode_ = false; + + std::function on_enter_light_sleep_mode_; + std::function on_exit_light_sleep_mode_; + std::function on_enter_deep_sleep_mode_; +}; diff --git a/main/boards/common/sy6970.cc b/main/boards/common/sy6970.cc new file mode 100644 index 0000000..8a45d75 --- /dev/null +++ b/main/boards/common/sy6970.cc @@ -0,0 +1,65 @@ +#include "sy6970.h" +#include "board.h" +#include "display.h" + +#include + +#define TAG "Sy6970" + +Sy6970::Sy6970(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { +} + +int Sy6970::GetChangingStatus() { + return (ReadReg(0x0B) >> 3) & 0x03; +} + +bool Sy6970::IsCharging() { + return GetChangingStatus() != 0; +} + +bool Sy6970::IsPowerGood() { + return (ReadReg(0x0B) & 0x04) != 0; +} + +bool Sy6970::IsChargingDone() { + return GetChangingStatus() == 3; +} + +int Sy6970::GetBatteryVoltage() { + uint8_t value = ReadReg(0x0E); + value &= 0x7F; + if (value == 0) { + return 0; + } + return value * 20 + 2304; +} + +int Sy6970::GetChargeTargetVoltage() { + uint8_t value = ReadReg(0x06); + value = (value & 0xFC) >> 2; + if (value > 0x30) { + return 4608; + } + return value * 16 + 3840; +} + +int Sy6970::GetBatteryLevel() { + int level = 0; + // 电池所能掉电的最低电压 + int battery_minimum_voltage = 3200; + int battery_voltage = GetBatteryVoltage(); + int charge_voltage_limit = GetChargeTargetVoltage(); + // ESP_LOGI(TAG, "battery_voltage: %d, charge_voltage_limit: %d", battery_voltage, charge_voltage_limit); + if (battery_voltage > battery_minimum_voltage && charge_voltage_limit > battery_minimum_voltage) { + level = (((float) battery_voltage - (float) battery_minimum_voltage) / ((float) charge_voltage_limit - (float) battery_minimum_voltage)) * 100.0; + } + // 不连接电池时读取的充电状态不稳定且battery_voltage有时会超过charge_voltage_limit + if (level > 100) { + level = 100; + } + return level; +} + +void Sy6970::PowerOff() { + WriteReg(0x09, 0B01100100); +} diff --git a/main/boards/common/sy6970.h b/main/boards/common/sy6970.h new file mode 100644 index 0000000..a2eaaca --- /dev/null +++ b/main/boards/common/sy6970.h @@ -0,0 +1,21 @@ +#ifndef __SY6970_H__ +#define __SY6970_H__ + +#include "i2c_device.h" + +class Sy6970 : public I2cDevice { +public: + Sy6970(i2c_master_bus_handle_t i2c_bus, uint8_t addr); + bool IsCharging(); + bool IsPowerGood(); + bool IsChargingDone(); + int GetBatteryLevel(); + void PowerOff(); + +private: + int GetChangingStatus(); + int GetBatteryVoltage(); + int GetChargeTargetVoltage(); +}; + +#endif \ No newline at end of file diff --git a/main/boards/common/system_reset.cc b/main/boards/common/system_reset.cc new file mode 100644 index 0000000..f51249b --- /dev/null +++ b/main/boards/common/system_reset.cc @@ -0,0 +1,72 @@ +#include "system_reset.h" + +#include +#include +#include +#include +#include +#include + + +#define TAG "SystemReset" + + +SystemReset::SystemReset(gpio_num_t reset_nvs_pin, gpio_num_t reset_factory_pin) : reset_nvs_pin_(reset_nvs_pin), reset_factory_pin_(reset_factory_pin) { + // Configure GPIO1, GPIO2 as INPUT, reset NVS flash if the button is pressed + gpio_config_t io_conf; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << reset_nvs_pin_) | (1ULL << reset_factory_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); +} + + +void SystemReset::CheckButtons() { + if (gpio_get_level(reset_factory_pin_) == 0) { + ESP_LOGI(TAG, "Button is pressed, reset to factory"); + ResetNvsFlash(); + ResetToFactory(); + } + + if (gpio_get_level(reset_nvs_pin_) == 0) { + ESP_LOGI(TAG, "Button is pressed, reset NVS flash"); + ResetNvsFlash(); + } +} + +void SystemReset::ResetNvsFlash() { + ESP_LOGI(TAG, "Resetting NVS flash"); + esp_err_t ret = nvs_flash_erase(); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to erase NVS flash"); + } + ret = nvs_flash_init(); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize NVS flash"); + } +} + +void SystemReset::ResetToFactory() { + ESP_LOGI(TAG, "Resetting to factory"); + // Erase otadata partition + const esp_partition_t* partition = esp_partition_find_first(ESP_PARTITION_TYPE_DATA, ESP_PARTITION_SUBTYPE_DATA_OTA, NULL); + if (partition == NULL) { + ESP_LOGE(TAG, "Failed to find otadata partition"); + return; + } + esp_partition_erase_range(partition, 0, partition->size); + ESP_LOGI(TAG, "Erased otadata partition"); + + // Reboot in 3 seconds + RestartInSeconds(3); +} + +void SystemReset::RestartInSeconds(int seconds) { + for (int i = seconds; i > 0; i--) { + ESP_LOGI(TAG, "Resetting in %d seconds", i); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + esp_restart(); +} diff --git a/main/boards/common/system_reset.h b/main/boards/common/system_reset.h new file mode 100644 index 0000000..7e78296 --- /dev/null +++ b/main/boards/common/system_reset.h @@ -0,0 +1,21 @@ +#ifndef _SYSTEM_RESET_H +#define _SYSTEM_RESET_H + +#include + +class SystemReset { +public: + SystemReset(gpio_num_t reset_nvs_pin, gpio_num_t reset_factory_pin); // 构造函数私有化 + void CheckButtons(); + +private: + gpio_num_t reset_nvs_pin_; + gpio_num_t reset_factory_pin_; + + void ResetNvsFlash(); + void ResetToFactory(); + void RestartInSeconds(int seconds); +}; + + +#endif diff --git a/main/boards/common/wifi_board.cc b/main/boards/common/wifi_board.cc new file mode 100644 index 0000000..20465ab --- /dev/null +++ b/main/boards/common/wifi_board.cc @@ -0,0 +1,267 @@ +#include "wifi_board.h" + +#include "display.h" +#include "application.h" +#include "system_info.h" +#include "settings.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include "afsk_demod.h" + +static const char *TAG = "WifiBoard"; + +WifiBoard::WifiBoard() { + Settings settings("wifi", true); + wifi_config_mode_ = settings.GetInt("force_ap") == 1; + if (wifi_config_mode_) { + ESP_LOGI(TAG, "force_ap is set to 1, reset to 0"); + settings.SetInt("force_ap", 0); + } +} + +std::string WifiBoard::GetBoardType() { + return "wifi"; +} + +void WifiBoard::EnterWifiConfigMode() { + auto& application = Application::GetInstance(); + application.SetDeviceState(kDeviceStateWifiConfiguring); + + auto& wifi_ap = WifiConfigurationAp::GetInstance(); + wifi_ap.SetLanguage(Lang::CODE); + wifi_ap.SetSsidPrefix("Xiaozhi"); + wifi_ap.Start(); + + // Wait 1.5 seconds to display board information + vTaskDelay(pdMS_TO_TICKS(1500)); + + // Display WiFi configuration AP SSID and web server URL + std::string hint = Lang::Strings::CONNECT_TO_HOTSPOT; + hint += wifi_ap.GetSsid(); + hint += Lang::Strings::ACCESS_VIA_BROWSER; + hint += wifi_ap.GetWebServerUrl(); + + // Announce WiFi configuration prompt + application.Alert(Lang::Strings::WIFI_CONFIG_MODE, hint.c_str(), "gear", Lang::Sounds::OGG_WIFICONFIG); + + #if CONFIG_USE_ACOUSTIC_WIFI_PROVISIONING + auto display = Board::GetInstance().GetDisplay(); + auto codec = Board::GetInstance().GetAudioCodec(); + int channel = 1; + if (codec) { + channel = codec->input_channels(); + } + ESP_LOGI(TAG, "Start receiving WiFi credentials from audio, input channels: %d", channel); + audio_wifi_config::ReceiveWifiCredentialsFromAudio(&application, &wifi_ap, display, channel); + #endif + + // Wait forever until reset after configuration + while (true) { + vTaskDelay(pdMS_TO_TICKS(10000)); + } +} + +void WifiBoard::StartNetwork() { + // User can press BOOT button while starting to enter WiFi configuration mode + if (wifi_config_mode_) { + EnterWifiConfigMode(); + return; + } + + // If no WiFi SSID is configured, enter WiFi configuration mode + auto& ssid_manager = SsidManager::GetInstance(); + auto ssid_list = ssid_manager.GetSsidList(); + if (ssid_list.empty()) { + wifi_config_mode_ = true; + EnterWifiConfigMode(); + return; + } + + auto& wifi_station = WifiStation::GetInstance(); + wifi_station.OnScanBegin([this]() { + auto display = Board::GetInstance().GetDisplay(); + display->ShowNotification(Lang::Strings::SCANNING_WIFI, 30000); + }); + wifi_station.OnConnect([this](const std::string& ssid) { + auto display = Board::GetInstance().GetDisplay(); + std::string notification = Lang::Strings::CONNECT_TO; + notification += ssid; + notification += "..."; + display->ShowNotification(notification.c_str(), 30000); + }); + wifi_station.OnConnected([this](const std::string& ssid) { + auto display = Board::GetInstance().GetDisplay(); + std::string notification = Lang::Strings::CONNECTED_TO; + notification += ssid; + display->ShowNotification(notification.c_str(), 30000); + }); + wifi_station.Start(); + + // Try to connect to WiFi, if failed, launch the WiFi configuration AP + if (!wifi_station.WaitForConnected(60 * 1000)) { + wifi_station.Stop(); + wifi_config_mode_ = true; + EnterWifiConfigMode(); + return; + } +} + +NetworkInterface* WifiBoard::GetNetwork() { + static EspNetwork network; + return &network; +} + +const char* WifiBoard::GetNetworkStateIcon() { + if (wifi_config_mode_) { + return FONT_AWESOME_WIFI; + } + auto& wifi_station = WifiStation::GetInstance(); + if (!wifi_station.IsConnected()) { + return FONT_AWESOME_WIFI_SLASH; + } + int8_t rssi = wifi_station.GetRssi(); + if (rssi >= -60) { + return FONT_AWESOME_WIFI; + } else if (rssi >= -70) { + return FONT_AWESOME_WIFI_FAIR; + } else { + return FONT_AWESOME_WIFI_WEAK; + } +} + +std::string WifiBoard::GetBoardJson() { + // Set the board type for OTA + auto& wifi_station = WifiStation::GetInstance(); + std::string board_json = R"({)"; + board_json += R"("type":")" + std::string(BOARD_TYPE) + R"(",)"; + board_json += R"("name":")" + std::string(BOARD_NAME) + R"(",)"; + if (!wifi_config_mode_) { + board_json += R"("ssid":")" + wifi_station.GetSsid() + R"(",)"; + board_json += R"("rssi":)" + std::to_string(wifi_station.GetRssi()) + R"(,)"; + board_json += R"("channel":)" + std::to_string(wifi_station.GetChannel()) + R"(,)"; + board_json += R"("ip":")" + wifi_station.GetIpAddress() + R"(",)"; + } + board_json += R"("mac":")" + SystemInfo::GetMacAddress() + R"(")"; + board_json += R"(})"; + return board_json; +} + +void WifiBoard::SetPowerSaveMode(bool enabled) { + auto& wifi_station = WifiStation::GetInstance(); + wifi_station.SetPowerSaveMode(enabled); +} + +void WifiBoard::ResetWifiConfiguration() { + // Set a flag and reboot the device to enter the network configuration mode + { + Settings settings("wifi", true); + settings.SetInt("force_ap", 1); + } + GetDisplay()->ShowNotification(Lang::Strings::ENTERING_WIFI_CONFIG_MODE); + vTaskDelay(pdMS_TO_TICKS(1000)); + // Reboot the device + esp_restart(); +} + +std::string WifiBoard::GetDeviceStatusJson() { + /* + * Return device status JSON + * + * The returned JSON structure is as follows: + * { + * "audio_speaker": { + * "volume": 70 + * }, + * "screen": { + * "brightness": 100, + * "theme": "light" + * }, + * "battery": { + * "level": 50, + * "charging": true + * }, + * "network": { + * "type": "wifi", + * "ssid": "Xiaozhi", + * "rssi": -60 + * }, + * "chip": { + * "temperature": 25 + * } + * } + */ + auto& board = Board::GetInstance(); + auto root = cJSON_CreateObject(); + + // Audio speaker + auto audio_speaker = cJSON_CreateObject(); + auto audio_codec = board.GetAudioCodec(); + if (audio_codec) { + cJSON_AddNumberToObject(audio_speaker, "volume", audio_codec->output_volume()); + } + cJSON_AddItemToObject(root, "audio_speaker", audio_speaker); + + // Screen brightness + auto backlight = board.GetBacklight(); + auto screen = cJSON_CreateObject(); + if (backlight) { + cJSON_AddNumberToObject(screen, "brightness", backlight->brightness()); + } + auto display = board.GetDisplay(); + if (display && display->height() > 64) { // For LCD display only + auto theme = display->GetTheme(); + if (theme != nullptr) { + cJSON_AddStringToObject(screen, "theme", theme->name().c_str()); + } + } + cJSON_AddItemToObject(root, "screen", screen); + + // Battery + int battery_level = 0; + bool charging = false; + bool discharging = false; + if (board.GetBatteryLevel(battery_level, charging, discharging)) { + cJSON* battery = cJSON_CreateObject(); + cJSON_AddNumberToObject(battery, "level", battery_level); + cJSON_AddBoolToObject(battery, "charging", charging); + cJSON_AddItemToObject(root, "battery", battery); + } + + // Network + auto network = cJSON_CreateObject(); + auto& wifi_station = WifiStation::GetInstance(); + cJSON_AddStringToObject(network, "type", "wifi"); + cJSON_AddStringToObject(network, "ssid", wifi_station.GetSsid().c_str()); + int rssi = wifi_station.GetRssi(); + if (rssi >= -60) { + cJSON_AddStringToObject(network, "signal", "strong"); + } else if (rssi >= -70) { + cJSON_AddStringToObject(network, "signal", "medium"); + } else { + cJSON_AddStringToObject(network, "signal", "weak"); + } + cJSON_AddItemToObject(root, "network", network); + + // Chip + float esp32temp = 0.0f; + if (board.GetTemperature(esp32temp)) { + auto chip = cJSON_CreateObject(); + cJSON_AddNumberToObject(chip, "temperature", esp32temp); + cJSON_AddItemToObject(root, "chip", chip); + } + + auto json_str = cJSON_PrintUnformatted(root); + std::string json(json_str); + cJSON_free(json_str); + cJSON_Delete(root); + return json; +} diff --git a/main/boards/common/wifi_board.h b/main/boards/common/wifi_board.h new file mode 100644 index 0000000..c84cf0f --- /dev/null +++ b/main/boards/common/wifi_board.h @@ -0,0 +1,24 @@ +#ifndef WIFI_BOARD_H +#define WIFI_BOARD_H + +#include "board.h" + +class WifiBoard : public Board { +protected: + bool wifi_config_mode_ = false; + void EnterWifiConfigMode(); + virtual std::string GetBoardJson() override; + +public: + WifiBoard(); + virtual std::string GetBoardType() override; + virtual void StartNetwork() override; + virtual NetworkInterface* GetNetwork() override; + virtual const char* GetNetworkStateIcon() override; + virtual void SetPowerSaveMode(bool enabled) override; + virtual void ResetWifiConfiguration(); + virtual AudioCodec* GetAudioCodec() override { return nullptr; } + virtual std::string GetDeviceStatusJson() override; +}; + +#endif // WIFI_BOARD_H diff --git a/main/boards/df-k10/README.md b/main/boards/df-k10/README.md new file mode 100644 index 0000000..310257b --- /dev/null +++ b/main/boards/df-k10/README.md @@ -0,0 +1,37 @@ +# DFRobot 行空板 K10 + +## 按键配置 +* A:短按-打断/唤醒,长按1s-音量调大 +* B:短按-打断/唤醒,长按1s-音量调小 + +## 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> DFRobot 行空板 K10 +``` + +**修改 psram 配置:** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> Octal Mode PSRAM +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/df-k10/config.h b/main/boards/df-k10/config.h new file mode 100644 index 0000000..5f8ad77 --- /dev/null +++ b/main/boards/df-k10/config.h @@ -0,0 +1,76 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_3 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_38 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_0 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_45 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR 0x23 + +#define BUILTIN_LED_GPIO GPIO_NUM_46 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +/* Expander */ +#define DRV_IO_EXP_INPUT_MASK (IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_12) + + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +/* DFRobot K10 Camera pins */ +#define PWDN_GPIO_NUM GPIO_NUM_NC +#define RESET_GPIO_NUM GPIO_NUM_NC +#define XCLK_GPIO_NUM GPIO_NUM_7 + +#define VSYNC_GPIO_NUM GPIO_NUM_4 +#define HREF_GPIO_NUM GPIO_NUM_5 +#define PCLK_GPIO_NUM GPIO_NUM_17 +#define SIOD_GPIO_NUM GPIO_NUM_20 +#define SIOC_GPIO_NUM GPIO_NUM_19 + +/* Camera pins */ +#define CAMERA_PIN_PWDN PWDN_GPIO_NUM +#define CAMERA_PIN_RESET RESET_GPIO_NUM +#define CAMERA_PIN_XCLK XCLK_GPIO_NUM +#define CAMERA_PIN_SIOD SIOD_GPIO_NUM +#define CAMERA_PIN_SIOC SIOC_GPIO_NUM + +#define CAMERA_PIN_D9 GPIO_NUM_6 +#define CAMERA_PIN_D8 GPIO_NUM_15 +#define CAMERA_PIN_D7 GPIO_NUM_16 +#define CAMERA_PIN_D6 GPIO_NUM_18 +#define CAMERA_PIN_D5 GPIO_NUM_9 +#define CAMERA_PIN_D4 GPIO_NUM_11 +#define CAMERA_PIN_D3 GPIO_NUM_10 +#define CAMERA_PIN_D2 GPIO_NUM_8 +#define CAMERA_PIN_VSYNC VSYNC_GPIO_NUM +#define CAMERA_PIN_HREF HREF_GPIO_NUM +#define CAMERA_PIN_PCLK PCLK_GPIO_NUM + +#define XCLK_FREQ_HZ 20000000 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/df-k10/config.json b/main/boards/df-k10/config.json new file mode 100644 index 0000000..55137d4 --- /dev/null +++ b/main/boards/df-k10/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "df-k10", + "sdkconfig_append": [ + "CONFIG_SPIRAM_MODE_OCT=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/df-k10/df_k10_board.cc b/main/boards/df-k10/df_k10_board.cc new file mode 100644 index 0000000..ab3e9e6 --- /dev/null +++ b/main/boards/df-k10/df_k10_board.cc @@ -0,0 +1,293 @@ +#include "wifi_board.h" +#include "k10_audio_codec.h" +#include "display/lcd_display.h" +#include "esp_lcd_ili9341.h" +#include "led_control.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "esp32_camera.h" + +#include "led/circular_strip.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include + +#include "esp_io_expander_tca95xx_16bit.h" + +#define TAG "DF-K10" + +class Df_K10Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander; + LcdDisplay *display_; + button_handle_t btn_a; + button_handle_t btn_b; + Esp32Camera* camera_; + + button_driver_t* btn_a_driver_ = nullptr; + button_driver_t* btn_b_driver_ = nullptr; + + CircularStrip* led_strip_; + + static Df_K10Board* instance_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_21; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_12; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + esp_err_t IoExpanderSetLevel(uint16_t pin_mask, uint8_t level) { + return esp_io_expander_set_level(io_expander, pin_mask, level); + } + + uint8_t IoExpanderGetLevel(uint16_t pin_mask) { + uint32_t pin_val = 0; + esp_io_expander_get_level(io_expander, DRV_IO_EXP_INPUT_MASK, &pin_val); + pin_mask &= DRV_IO_EXP_INPUT_MASK; + return (uint8_t)((pin_val & pin_mask) ? 1 : 0); + } + + void InitializeIoExpander() { + esp_io_expander_new_i2c_tca95xx_16bit( + i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_000, &io_expander); + + esp_err_t ret; + ret = esp_io_expander_print_state(io_expander); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Print state failed: %s", esp_err_to_name(ret)); + } + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0, + IO_EXPANDER_OUTPUT); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Set direction failed: %s", esp_err_to_name(ret)); + } + ret = esp_io_expander_set_level(io_expander, 0, 1); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Set level failed: %s", esp_err_to_name(ret)); + } + ret = esp_io_expander_set_dir( + io_expander, DRV_IO_EXP_INPUT_MASK, + IO_EXPANDER_INPUT); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Set direction failed: %s", esp_err_to_name(ret)); + } + } + + void InitializeButtons() { + instance_ = this; + + // Button A + button_config_t btn_a_config = { + .long_press_time = 1000, + .short_press_time = 0 + }; + btn_a_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + btn_a_driver_->enable_power_save = false; + btn_a_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !instance_->IoExpanderGetLevel(IO_EXPANDER_PIN_NUM_2); + }; + ESP_ERROR_CHECK(iot_button_create(&btn_a_config, btn_a_driver_, &btn_a)); + iot_button_register_cb(btn_a, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + app.ToggleChatState(); + }, this); + iot_button_register_cb(btn_a, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto codec = self->GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + self->GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }, this); + + // Button B + button_config_t btn_b_config = { + .long_press_time = 1000, + .short_press_time = 0 + }; + btn_b_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + btn_b_driver_->enable_power_save = false; + btn_b_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !instance_->IoExpanderGetLevel(IO_EXPANDER_PIN_NUM_12); + }; + ESP_ERROR_CHECK(iot_button_create(&btn_b_config, btn_b_driver_, &btn_b)); + iot_button_register_cb(btn_b, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + app.ToggleChatState(); + }, this); + iot_button_register_cb(btn_b, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto codec = self->GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + self->GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }, this); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D2, + [1] = CAMERA_PIN_D3, + [2] = CAMERA_PIN_D4, + [3] = CAMERA_PIN_D5, + [4] = CAMERA_PIN_D6, + [5] = CAMERA_PIN_D7, + [6] = CAMERA_PIN_D8, + [7] = CAMERA_PIN_D9, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + + void InitializeIli9341Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_14; + io_config.dc_gpio_num = GPIO_NUM_13; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.bits_per_pixel = 16; + panel_config.color_space = ESP_LCD_COLOR_SPACE_BGR; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeIot() { + led_strip_ = new CircularStrip(BUILTIN_LED_GPIO, 3); + new LedStripControl(led_strip_); + } + +public: + Df_K10Board() { + InitializeI2c(); + InitializeIoExpander(); + InitializeSpi(); + InitializeIli9341Display(); + InitializeButtons(); + InitializeIot(); + InitializeCamera(); + } + + virtual Led* GetLed() override { + return led_strip_; + } + + virtual AudioCodec *GetAudioCodec() override { + static K10AudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Display *GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(Df_K10Board); + +Df_K10Board* Df_K10Board::instance_ = nullptr; diff --git a/main/boards/df-k10/k10_audio_codec.cc b/main/boards/df-k10/k10_audio_codec.cc new file mode 100644 index 0000000..5a30948 --- /dev/null +++ b/main/boards/df-k10/k10_audio_codec.cc @@ -0,0 +1,225 @@ +#include "k10_audio_codec.h" + +#include +#include +#include +#include + +static const char TAG[] = "K10AudioCodec"; + +K10AudioCodec::K10AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7210_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + audio_codec_i2c_cfg_t i2c_cfg = { + .port = I2C_NUM_1, + .addr = es7210_addr, + .bus_handle = i2c_master_handle, + }; + const audio_codec_ctrl_if_t *in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7243e_codec_cfg_t es7243e_cfg = { + .ctrl_if = in_ctrl_if_, + }; + const audio_codec_if_t *in_codec_if_ = es7243e_codec_new(&es7243e_cfg); + assert(in_codec_if_ != NULL); + + esp_codec_dev_cfg_t codec_es7243e_dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_IN, + .codec_if = in_codec_if_, + .data_if = data_if_, + }; + input_dev_ = esp_codec_dev_new(&codec_es7243e_dev_cfg); + + assert(input_dev_ != NULL); + + ESP_LOGI(TAG, "DF-K10 AudioDevice initialized"); +} + +K10AudioCodec::~K10AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void K10AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + // .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + i2s_tdm_config_t tdm_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + .bclk_div = 8, + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = i2s_tdm_slot_mask_t(I2S_TDM_SLOT0 | I2S_TDM_SLOT1 | I2S_TDM_SLOT2 | I2S_TDM_SLOT3), + .ws_width = I2S_TDM_AUTO_WS_WIDTH, + .ws_pol = false, + .bit_shift = true, + .left_align = false, + .big_endian = false, + .bit_order_lsb = false, + .skip_mask = false, + .total_slot = I2S_TDM_AUTO_SLOT_NUM + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = I2S_GPIO_UNUSED, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_tdm_mode(rx_handle_, &tdm_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void K10AudioCodec::SetOutputVolume(int volume) { + AudioCodec::SetOutputVolume(volume); +} + +void K10AudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 4, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + if (input_reference_) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, 37.5)); //麦克风增益解决收音太小的问题 + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void K10AudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + AudioCodec::SetOutputVolume(output_volume_); + AudioCodec::EnableOutput(enable); +} + +int K10AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int K10AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + std::vector buffer(samples * 2); // Allocate buffer for 2x samples + + // Apply volume adjustment (same as before) + int32_t volume_factor = pow(double(output_volume_) / 100.0, 2) * 65536; + for (int i = 0; i < samples; i++) { + int64_t temp = int64_t(data[i]) * volume_factor; + if (temp > INT32_MAX) { + buffer[i * 2] = INT32_MAX; + } else if (temp < INT32_MIN) { + buffer[i * 2] = INT32_MIN; + } else { + buffer[i * 2] = static_cast(temp); + } + + // Repeat each sample for slow playback (assuming mono audio) + buffer[i * 2 + 1] = buffer[i * 2]; + } + + size_t bytes_written; + ESP_ERROR_CHECK(i2s_channel_write(tx_handle_, buffer.data(), samples * 2 * sizeof(int32_t), &bytes_written, portMAX_DELAY)); + return bytes_written / sizeof(int32_t); + } + return samples; +} diff --git a/main/boards/df-k10/k10_audio_codec.h b/main/boards/df-k10/k10_audio_codec.h new file mode 100644 index 0000000..061adbe --- /dev/null +++ b/main/boards/df-k10/k10_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _BOX_AUDIO_CODEC_H +#define _BOX_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class K10AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + K10AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7210_addr, bool input_reference); + virtual ~K10AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/df-k10/led_control.cc b/main/boards/df-k10/led_control.cc new file mode 100644 index 0000000..ce5164a --- /dev/null +++ b/main/boards/df-k10/led_control.cc @@ -0,0 +1,124 @@ +#include "led_control.h" +#include "settings.h" +#include "mcp_server.h" +#include + +#define TAG "LedStripControl" + + +int LedStripControl::LevelToBrightness(int level) const { + if (level < 0) level = 0; + if (level > 8) level = 8; + return (1 << level) - 1; // 2^n - 1 +} + +StripColor LedStripControl::RGBToColor(int red, int green, int blue) { + return {static_cast(red), static_cast(green), static_cast(blue)}; +} + +LedStripControl::LedStripControl(CircularStrip* led_strip) + : led_strip_(led_strip) { + // 从设置中读取亮度等级 + Settings settings("led_strip"); + brightness_level_ = settings.GetInt("brightness", 4); // 默认等级4 + led_strip_->SetBrightness(LevelToBrightness(brightness_level_), 4); + + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.led_strip.get_brightness", + "Get the brightness of the led strip (0-8)", + PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return brightness_level_; + }); + + mcp_server.AddTool("self.led_strip.set_brightness", + "Set the brightness of the led strip (0-8)", + PropertyList({ + Property("level", kPropertyTypeInteger, 0, 8) + }), [this](const PropertyList& properties) -> ReturnValue { + int level = properties["level"].value(); + ESP_LOGI(TAG, "Set LedStrip brightness level to %d", level); + brightness_level_ = level; + led_strip_->SetBrightness(LevelToBrightness(brightness_level_), 4); + + // 保存设置 + Settings settings("led_strip", true); + settings.SetInt("brightness", brightness_level_); + + return true; + }); + + mcp_server.AddTool("self.led_strip.set_single_color", + "Set the color of a single led.", + PropertyList({ + Property("index", kPropertyTypeInteger, 0, 2), + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int index = properties["index"].value(); + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + ESP_LOGI(TAG, "Set led strip single color %d to %d, %d, %d", + index, red, green, blue); + led_strip_->SetSingleColor(index, RGBToColor(red, green, blue)); + return true; + }); + + mcp_server.AddTool("self.led_strip.set_all_color", + "Set the color of all leds.", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + ESP_LOGI(TAG, "Set led strip all color to %d, %d, %d", + red, green, blue); + led_strip_->SetAllColor(RGBToColor(red, green, blue)); + return true; + }); + + mcp_server.AddTool("self.led_strip.blink", + "Blink the led strip. (闪烁)", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255), + Property("interval", kPropertyTypeInteger, 0, 1000) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + int interval = properties["interval"].value(); + ESP_LOGI(TAG, "Blink led strip with color %d, %d, %d, interval %dms", + red, green, blue, interval); + led_strip_->Blink(RGBToColor(red, green, blue), interval); + return true; + }); + + mcp_server.AddTool("self.led_strip.scroll", + "Scroll the led strip. (跑马灯)", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255), + Property("length", kPropertyTypeInteger, 1, 7), + Property("interval", kPropertyTypeInteger, 0, 1000) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + int interval = properties["interval"].value(); + int length = properties["length"].value(); + ESP_LOGI(TAG, "Scroll led strip with color %d, %d, %d, length %d, interval %dms", + red, green, blue, length, interval); + StripColor low = RGBToColor(4, 4, 4); + StripColor high = RGBToColor(red, green, blue); + led_strip_->Scroll(low, high, length, interval); + return true; + }); + +} diff --git a/main/boards/df-k10/led_control.h b/main/boards/df-k10/led_control.h new file mode 100644 index 0000000..30e1020 --- /dev/null +++ b/main/boards/df-k10/led_control.h @@ -0,0 +1,18 @@ +#ifndef LED_CONTROL_H +#define LED_CONTROL_H + +#include "led/circular_strip.h" + +class LedStripControl { +private: + CircularStrip* led_strip_; + int brightness_level_; // 亮度等级 (0-8) + + int LevelToBrightness(int level) const; // 将等级转换为实际亮度值 + StripColor RGBToColor(int red, int green, int blue); + +public: + explicit LedStripControl(CircularStrip* led_strip); +}; + +#endif // LED_STRIP_CONTROL_H diff --git a/main/boards/df-s3-ai-cam/README.md b/main/boards/df-s3-ai-cam/README.md new file mode 100644 index 0000000..304483c --- /dev/null +++ b/main/boards/df-s3-ai-cam/README.md @@ -0,0 +1,54 @@ +# DFRobot ESP32-S3 AI智能摄像头模块 + +## 介绍 +ESP32-S3 AI CAM是一款基于ESP32-S3芯片设计的智能摄像头模组,专为视频图像处理和语音交互打造,适用于视频监控、边缘图像识别、语音对话等AI项目。 +![](https://ws.dfrobot.com.cn/FsTrGbrX2NZAwzWS8OSQGOGikuYA) + +[点击查看详细介绍](https://wiki.dfrobot.com.cn/SKU_DFR1154_ESP32_S3_AI_CAM) + +[点击查看视觉功能演示](https://www.bilibili.com/video/BV1ktjSzNEUU/) + +# 特性 +* 使用PDM麦克风 +* 板载 OV3660 摄像头 + +## 按键配置 +* BOOT:短按-打断/唤醒 + +## 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> DFRobot ESP32-S3 AI智能摄像头模块 +``` + +**修改 psram 配置:** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> Octal Mode PSRAM +``` + +**修改 WiFi 发射功率 为 10:** + +``` +Component config -> PHY -> (10)Max WiFi TX power (dBm) +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/df-s3-ai-cam/config.h b/main/boards/df-s3-ai-cam/config.h new file mode 100644 index 0000000..50dcc85 --- /dev/null +++ b/main/boards/df-s3-ai-cam/config.h @@ -0,0 +1,63 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_38 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_42 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_45 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_46 +#define AUDIO_I2S_SPK_GPIO_GAIN GPIO_NUM_41 + +#define BUILTIN_LED_GPIO GPIO_NUM_3 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC +#define RESET_NVS_BUTTON_GPIO GPIO_NUM_NC +#define RESET_FACTORY_BUTTON_GPIO GPIO_NUM_NC + +/* DFRobot Camera pins */ +#define PWDN_GPIO_NUM GPIO_NUM_NC +#define RESET_GPIO_NUM GPIO_NUM_NC +#define XCLK_GPIO_NUM GPIO_NUM_5 +#define Y9_GPIO_NUM GPIO_NUM_4 +#define Y8_GPIO_NUM GPIO_NUM_6 +#define Y7_GPIO_NUM GPIO_NUM_7 +#define Y6_GPIO_NUM GPIO_NUM_14 +#define Y5_GPIO_NUM GPIO_NUM_17 +#define Y4_GPIO_NUM GPIO_NUM_21 +#define Y3_GPIO_NUM GPIO_NUM_18 +#define Y2_GPIO_NUM GPIO_NUM_16 +#define VSYNC_GPIO_NUM GPIO_NUM_1 +#define HREF_GPIO_NUM GPIO_NUM_2 +#define PCLK_GPIO_NUM GPIO_NUM_15 +#define SIOD_GPIO_NUM GPIO_NUM_8 +#define SIOC_GPIO_NUM GPIO_NUM_9 + +/* Camera pins */ +#define CAMERA_PIN_PWDN PWDN_GPIO_NUM +#define CAMERA_PIN_RESET RESET_GPIO_NUM +#define CAMERA_PIN_XCLK XCLK_GPIO_NUM +#define CAMERA_PIN_SIOD SIOD_GPIO_NUM +#define CAMERA_PIN_SIOC SIOC_GPIO_NUM + +#define CAMERA_PIN_D7 Y9_GPIO_NUM +#define CAMERA_PIN_D6 Y8_GPIO_NUM +#define CAMERA_PIN_D5 Y7_GPIO_NUM +#define CAMERA_PIN_D4 Y6_GPIO_NUM +#define CAMERA_PIN_D3 Y5_GPIO_NUM +#define CAMERA_PIN_D2 Y4_GPIO_NUM +#define CAMERA_PIN_D1 Y3_GPIO_NUM +#define CAMERA_PIN_D0 Y2_GPIO_NUM +#define CAMERA_PIN_VSYNC VSYNC_GPIO_NUM +#define CAMERA_PIN_HREF HREF_GPIO_NUM +#define CAMERA_PIN_PCLK PCLK_GPIO_NUM + +#define XCLK_FREQ_HZ 20000000 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/df-s3-ai-cam/config.json b/main/boards/df-s3-ai-cam/config.json new file mode 100644 index 0000000..ff50ca6 --- /dev/null +++ b/main/boards/df-s3-ai-cam/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "df-s3-ai-cam", + "sdkconfig_append": [ + "CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=10", + "CONFIG_ESP_PHY_MAX_TX_POWER=10", + "CONFIG_SPIRAM_MODE_OCT=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/df-s3-ai-cam/df_s3_ai_cam.cc b/main/boards/df-s3-ai-cam/df_s3_ai_cam.cc new file mode 100644 index 0000000..fbdef6c --- /dev/null +++ b/main/boards/df-s3-ai-cam/df_s3_ai_cam.cc @@ -0,0 +1,103 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "esp32_camera.h" + +#include "led/gpio_led.h" +#include +#include +#include +#include + +#define TAG "DfrobotEsp32S3AiCam" + +class DfrobotEsp32S3AiCam : public WifiBoard { + private: + Button boot_button_; + Esp32Camera* camera_; + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = CAMERA_PIN_SIOC, + .sda_pin = CAMERA_PIN_SIOD, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + camera_->SetVFlip(1); + } + + public: + DfrobotEsp32S3AiCam() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeButtons(); + InitializeCamera(); + } + + // Wakenet model only + + virtual Led* GetLed() override { + static GpioLed led(BUILTIN_LED_GPIO, 0); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplexPdm audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, + AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(DfrobotEsp32S3AiCam); diff --git a/main/boards/doit-s3-aibox/README.md b/main/boards/doit-s3-aibox/README.md new file mode 100644 index 0000000..006b9e7 --- /dev/null +++ b/main/boards/doit-s3-aibox/README.md @@ -0,0 +1,42 @@ +# 四博智联AI陪伴盒子 + +# 特性 +* 使用PDM麦克风 +* 使用共阳极LED + +## 按键配置 +* BUTTON3:短按-打断/唤醒 +* BUTTON1:音量+ +* BUTTON2:音量- + +## 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> 四博智联AI陪伴盒子 +``` + +**修改 psram 配置:** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> Octal Mode PSRAM +``` + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/doit-s3-aibox/config.h b/main/boards/doit-s3-aibox/config.h new file mode 100644 index 0000000..9c44200 --- /dev/null +++ b/main/boards/doit-s3-aibox/config.h @@ -0,0 +1,29 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_41 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_40 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_42 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_18 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_17 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +/* +IO9: BUTTON2 +IO10: BUTTON3 引出:KEY3 +IO15: BUTTON1 +*/ +#define BUILTIN_LED_GPIO GPIO_NUM_45 +#define BOOT_BUTTON_GPIO GPIO_NUM_10 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_15 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_9 +#define RESET_NVS_BUTTON_GPIO GPIO_NUM_10 +#define RESET_FACTORY_BUTTON_GPIO GPIO_NUM_NC + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/doit-s3-aibox/config.json b/main/boards/doit-s3-aibox/config.json new file mode 100644 index 0000000..a9de834 --- /dev/null +++ b/main/boards/doit-s3-aibox/config.json @@ -0,0 +1,10 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "doit-s3-aibox", + "sdkconfig_append": [ + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/doit-s3-aibox/doit_s3_aibox.cc b/main/boards/doit-s3-aibox/doit_s3_aibox.cc new file mode 100644 index 0000000..54fd9df --- /dev/null +++ b/main/boards/doit-s3-aibox/doit_s3_aibox.cc @@ -0,0 +1,137 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/gpio_led.h" +#include +#include +#include +#include + +#define TAG "DoitS3AiBox" + +class DoitS3AiBox : public WifiBoard { +private: + Button boot_button_; + Button touch_button_; + Button volume_up_button_; + Button volume_down_button_; + uint8_t click_times; + uint32_t check_time; + + void InitializeButtons() { + click_times = 0; + check_time = 0; + boot_button_.OnClick([this]() { + if(click_times==0) { + check_time = esp_timer_get_time()/1000; + } + if(esp_timer_get_time()/1000-check_time<1000) { + click_times++; + check_time = esp_timer_get_time()/1000; + } else { + click_times = 0; + check_time = 0; + } + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + click_times++; + ESP_LOGI(TAG, "DoubleClick times %d", click_times); + if(click_times==3) { + click_times = 0; + ResetWifiConfiguration(); + } + }); + + boot_button_.OnLongPress([this]() { + if(click_times>=3) { + ResetWifiConfiguration(); + } else { + click_times = 0; + check_time = 0; + } + }); + + touch_button_.OnPressDown([this]() { + click_times = 0; + Application::GetInstance().StartListening(); + }); + touch_button_.OnPressUp([this]() { + click_times = 0; + Application::GetInstance().StopListening(); + }); + + volume_up_button_.OnClick([this]() { + click_times = 0; + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + }); + + volume_up_button_.OnLongPress([this]() { + click_times = 0; + GetAudioCodec()->SetOutputVolume(100); + }); + + volume_down_button_.OnClick([this]() { + click_times = 0; + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + }); + + volume_down_button_.OnLongPress([this]() { + click_times = 0; + GetAudioCodec()->SetOutputVolume(0); + }); + } + + void InitializeGpio(gpio_num_t gpio_num_) { + gpio_config_t config = { + .pin_bit_mask = (1ULL << gpio_num_), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_ENABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + ESP_ERROR_CHECK(gpio_config(&config)); + gpio_set_level(gpio_num_, 1); + } + +public: + DoitS3AiBox() : + boot_button_(BOOT_BUTTON_GPIO), + touch_button_(TOUCH_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO){ + // 上拉io48 置高电平 + InitializeGpio(GPIO_NUM_48); + InitializeButtons(); + } + + virtual Led* GetLed() override { + static GpioLed led(BUILTIN_LED_GPIO, 1); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplexPdm audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } +}; + +DECLARE_BOARD(DoitS3AiBox); diff --git a/main/boards/du-chatx/config.h b/main/boards/du-chatx/config.h new file mode 100644 index 0000000..729e1f4 --- /dev/null +++ b/main/boards/du-chatx/config.h @@ -0,0 +1,40 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_39 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_38 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_40 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_42 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_2 + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_9 +#define DISPLAY_MOSI_PIN GPIO_NUM_18 +#define DISPLAY_CLK_PIN GPIO_NUM_17 +#define DISPLAY_DC_PIN GPIO_NUM_8 +#define DISPLAY_RST_PIN GPIO_NUM_20 +#define DISPLAY_CS_PIN GPIO_NUM_16 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 2 +#define DISPLAY_OFFSET_Y 1 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/du-chatx/config.json b/main/boards/du-chatx/config.json new file mode 100644 index 0000000..e6abd31 --- /dev/null +++ b/main/boards/du-chatx/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "du-chatx", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/du-chatx/du-chatx-wifi.cc b/main/boards/du-chatx/du-chatx-wifi.cc new file mode 100644 index 0000000..d9eea67 --- /dev/null +++ b/main/boards/du-chatx/du-chatx-wifi.cc @@ -0,0 +1,164 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" +#include "power_manager.h" +#include "power_save_timer.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "DuChatX" + +class DuChatX : public WifiBoard { +private: + Button boot_button_; + LcdDisplay *display_; + PowerManager *power_manager_; + PowerSaveTimer *power_save_timer_; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_6); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_1); + rtc_gpio_set_direction(GPIO_NUM_1, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_1, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_1, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_1); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel_ IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel_)); + esp_lcd_panel_reset(panel_); + esp_lcd_panel_init(panel_); + esp_lcd_panel_invert_color(panel_, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel_,DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y,DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + DuChatX() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + InitializePowerSaveTimer(); + InitializePowerManager(); + } + + virtual Led *GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec *GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Backlight *GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(DuChatX); diff --git a/main/boards/du-chatx/power_manager.h b/main/boards/du-chatx/power_manager.h new file mode 100644 index 0000000..8438880 --- /dev/null +++ b/main/boards/du-chatx/power_manager.h @@ -0,0 +1,186 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_5, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1120, 0}, + {1140, 20}, + {1160, 40}, + {1170, 60}, + {1190, 80}, + {1217, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_5, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/echoear/EchoEar.cc b/main/boards/echoear/EchoEar.cc new file mode 100644 index 0000000..9e5f5c7 --- /dev/null +++ b/main/boards/echoear/EchoEar.cc @@ -0,0 +1,633 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "display/emote_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "backlight.h" + +#include +#include + +#include +#include +#include "i2c_device.h" +#include +#include +#include +#include "esp_lcd_touch_cst816s.h" +#include "touch.h" + +#include "driver/temperature_sensor.h" +#include +#include +#include + +#define TAG "EchoEar" + + +temperature_sensor_handle_t temp_sensor = NULL; +static const st77916_lcd_init_cmd_t vendor_specific_init_yysj[] = { + {0xF0, (uint8_t []){0x28}, 1, 0}, + {0xF2, (uint8_t []){0x28}, 1, 0}, + {0x73, (uint8_t []){0xF0}, 1, 0}, + {0x7C, (uint8_t []){0xD1}, 1, 0}, + {0x83, (uint8_t []){0xE0}, 1, 0}, + {0x84, (uint8_t []){0x61}, 1, 0}, + {0xF2, (uint8_t []){0x82}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x01}, 1, 0}, + {0xF1, (uint8_t []){0x01}, 1, 0}, + {0xB0, (uint8_t []){0x56}, 1, 0}, + {0xB1, (uint8_t []){0x4D}, 1, 0}, + {0xB2, (uint8_t []){0x24}, 1, 0}, + {0xB4, (uint8_t []){0x87}, 1, 0}, + {0xB5, (uint8_t []){0x44}, 1, 0}, + {0xB6, (uint8_t []){0x8B}, 1, 0}, + {0xB7, (uint8_t []){0x40}, 1, 0}, + {0xB8, (uint8_t []){0x86}, 1, 0}, + {0xBA, (uint8_t []){0x00}, 1, 0}, + {0xBB, (uint8_t []){0x08}, 1, 0}, + {0xBC, (uint8_t []){0x08}, 1, 0}, + {0xBD, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x80}, 1, 0}, + {0xC1, (uint8_t []){0x10}, 1, 0}, + {0xC2, (uint8_t []){0x37}, 1, 0}, + {0xC3, (uint8_t []){0x80}, 1, 0}, + {0xC4, (uint8_t []){0x10}, 1, 0}, + {0xC5, (uint8_t []){0x37}, 1, 0}, + {0xC6, (uint8_t []){0xA9}, 1, 0}, + {0xC7, (uint8_t []){0x41}, 1, 0}, + {0xC8, (uint8_t []){0x01}, 1, 0}, + {0xC9, (uint8_t []){0xA9}, 1, 0}, + {0xCA, (uint8_t []){0x41}, 1, 0}, + {0xCB, (uint8_t []){0x01}, 1, 0}, + {0xD0, (uint8_t []){0x91}, 1, 0}, + {0xD1, (uint8_t []){0x68}, 1, 0}, + {0xD2, (uint8_t []){0x68}, 1, 0}, + {0xF5, (uint8_t []){0x00, 0xA5}, 2, 0}, + {0xDD, (uint8_t []){0x4F}, 1, 0}, + {0xDE, (uint8_t []){0x4F}, 1, 0}, + {0xF1, (uint8_t []){0x10}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0xF0, 0x0A, 0x10, 0x09, 0x09, 0x36, 0x35, 0x33, 0x4A, 0x29, 0x15, 0x15, 0x2E, 0x34}, 14, 0}, + {0xE1, (uint8_t []){0xF0, 0x0A, 0x0F, 0x08, 0x08, 0x05, 0x34, 0x33, 0x4A, 0x39, 0x15, 0x15, 0x2D, 0x33}, 14, 0}, + {0xF0, (uint8_t []){0x10}, 1, 0}, + {0xF3, (uint8_t []){0x10}, 1, 0}, + {0xE0, (uint8_t []){0x07}, 1, 0}, + {0xE1, (uint8_t []){0x00}, 1, 0}, + {0xE2, (uint8_t []){0x00}, 1, 0}, + {0xE3, (uint8_t []){0x00}, 1, 0}, + {0xE4, (uint8_t []){0xE0}, 1, 0}, + {0xE5, (uint8_t []){0x06}, 1, 0}, + {0xE6, (uint8_t []){0x21}, 1, 0}, + {0xE7, (uint8_t []){0x01}, 1, 0}, + {0xE8, (uint8_t []){0x05}, 1, 0}, + {0xE9, (uint8_t []){0x02}, 1, 0}, + {0xEA, (uint8_t []){0xDA}, 1, 0}, + {0xEB, (uint8_t []){0x00}, 1, 0}, + {0xEC, (uint8_t []){0x00}, 1, 0}, + {0xED, (uint8_t []){0x0F}, 1, 0}, + {0xEE, (uint8_t []){0x00}, 1, 0}, + {0xEF, (uint8_t []){0x00}, 1, 0}, + {0xF8, (uint8_t []){0x00}, 1, 0}, + {0xF9, (uint8_t []){0x00}, 1, 0}, + {0xFA, (uint8_t []){0x00}, 1, 0}, + {0xFB, (uint8_t []){0x00}, 1, 0}, + {0xFC, (uint8_t []){0x00}, 1, 0}, + {0xFD, (uint8_t []){0x00}, 1, 0}, + {0xFE, (uint8_t []){0x00}, 1, 0}, + {0xFF, (uint8_t []){0x00}, 1, 0}, + {0x60, (uint8_t []){0x40}, 1, 0}, + {0x61, (uint8_t []){0x04}, 1, 0}, + {0x62, (uint8_t []){0x00}, 1, 0}, + {0x63, (uint8_t []){0x42}, 1, 0}, + {0x64, (uint8_t []){0xD9}, 1, 0}, + {0x65, (uint8_t []){0x00}, 1, 0}, + {0x66, (uint8_t []){0x00}, 1, 0}, + {0x67, (uint8_t []){0x00}, 1, 0}, + {0x68, (uint8_t []){0x00}, 1, 0}, + {0x69, (uint8_t []){0x00}, 1, 0}, + {0x6A, (uint8_t []){0x00}, 1, 0}, + {0x6B, (uint8_t []){0x00}, 1, 0}, + {0x70, (uint8_t []){0x40}, 1, 0}, + {0x71, (uint8_t []){0x03}, 1, 0}, + {0x72, (uint8_t []){0x00}, 1, 0}, + {0x73, (uint8_t []){0x42}, 1, 0}, + {0x74, (uint8_t []){0xD8}, 1, 0}, + {0x75, (uint8_t []){0x00}, 1, 0}, + {0x76, (uint8_t []){0x00}, 1, 0}, + {0x77, (uint8_t []){0x00}, 1, 0}, + {0x78, (uint8_t []){0x00}, 1, 0}, + {0x79, (uint8_t []){0x00}, 1, 0}, + {0x7A, (uint8_t []){0x00}, 1, 0}, + {0x7B, (uint8_t []){0x00}, 1, 0}, + {0x80, (uint8_t []){0x48}, 1, 0}, + {0x81, (uint8_t []){0x00}, 1, 0}, + {0x82, (uint8_t []){0x06}, 1, 0}, + {0x83, (uint8_t []){0x02}, 1, 0}, + {0x84, (uint8_t []){0xD6}, 1, 0}, + {0x85, (uint8_t []){0x04}, 1, 0}, + {0x86, (uint8_t []){0x00}, 1, 0}, + {0x87, (uint8_t []){0x00}, 1, 0}, + {0x88, (uint8_t []){0x48}, 1, 0}, + {0x89, (uint8_t []){0x00}, 1, 0}, + {0x8A, (uint8_t []){0x08}, 1, 0}, + {0x8B, (uint8_t []){0x02}, 1, 0}, + {0x8C, (uint8_t []){0xD8}, 1, 0}, + {0x8D, (uint8_t []){0x04}, 1, 0}, + {0x8E, (uint8_t []){0x00}, 1, 0}, + {0x8F, (uint8_t []){0x00}, 1, 0}, + {0x90, (uint8_t []){0x48}, 1, 0}, + {0x91, (uint8_t []){0x00}, 1, 0}, + {0x92, (uint8_t []){0x0A}, 1, 0}, + {0x93, (uint8_t []){0x02}, 1, 0}, + {0x94, (uint8_t []){0xDA}, 1, 0}, + {0x95, (uint8_t []){0x04}, 1, 0}, + {0x96, (uint8_t []){0x00}, 1, 0}, + {0x97, (uint8_t []){0x00}, 1, 0}, + {0x98, (uint8_t []){0x48}, 1, 0}, + {0x99, (uint8_t []){0x00}, 1, 0}, + {0x9A, (uint8_t []){0x0C}, 1, 0}, + {0x9B, (uint8_t []){0x02}, 1, 0}, + {0x9C, (uint8_t []){0xDC}, 1, 0}, + {0x9D, (uint8_t []){0x04}, 1, 0}, + {0x9E, (uint8_t []){0x00}, 1, 0}, + {0x9F, (uint8_t []){0x00}, 1, 0}, + {0xA0, (uint8_t []){0x48}, 1, 0}, + {0xA1, (uint8_t []){0x00}, 1, 0}, + {0xA2, (uint8_t []){0x05}, 1, 0}, + {0xA3, (uint8_t []){0x02}, 1, 0}, + {0xA4, (uint8_t []){0xD5}, 1, 0}, + {0xA5, (uint8_t []){0x04}, 1, 0}, + {0xA6, (uint8_t []){0x00}, 1, 0}, + {0xA7, (uint8_t []){0x00}, 1, 0}, + {0xA8, (uint8_t []){0x48}, 1, 0}, + {0xA9, (uint8_t []){0x00}, 1, 0}, + {0xAA, (uint8_t []){0x07}, 1, 0}, + {0xAB, (uint8_t []){0x02}, 1, 0}, + {0xAC, (uint8_t []){0xD7}, 1, 0}, + {0xAD, (uint8_t []){0x04}, 1, 0}, + {0xAE, (uint8_t []){0x00}, 1, 0}, + {0xAF, (uint8_t []){0x00}, 1, 0}, + {0xB0, (uint8_t []){0x48}, 1, 0}, + {0xB1, (uint8_t []){0x00}, 1, 0}, + {0xB2, (uint8_t []){0x09}, 1, 0}, + {0xB3, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0xD9}, 1, 0}, + {0xB5, (uint8_t []){0x04}, 1, 0}, + {0xB6, (uint8_t []){0x00}, 1, 0}, + {0xB7, (uint8_t []){0x00}, 1, 0}, + {0xB8, (uint8_t []){0x48}, 1, 0}, + {0xB9, (uint8_t []){0x00}, 1, 0}, + {0xBA, (uint8_t []){0x0B}, 1, 0}, + {0xBB, (uint8_t []){0x02}, 1, 0}, + {0xBC, (uint8_t []){0xDB}, 1, 0}, + {0xBD, (uint8_t []){0x04}, 1, 0}, + {0xBE, (uint8_t []){0x00}, 1, 0}, + {0xBF, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x10}, 1, 0}, + {0xC1, (uint8_t []){0x47}, 1, 0}, + {0xC2, (uint8_t []){0x56}, 1, 0}, + {0xC3, (uint8_t []){0x65}, 1, 0}, + {0xC4, (uint8_t []){0x74}, 1, 0}, + {0xC5, (uint8_t []){0x88}, 1, 0}, + {0xC6, (uint8_t []){0x99}, 1, 0}, + {0xC7, (uint8_t []){0x01}, 1, 0}, + {0xC8, (uint8_t []){0xBB}, 1, 0}, + {0xC9, (uint8_t []){0xAA}, 1, 0}, + {0xD0, (uint8_t []){0x10}, 1, 0}, + {0xD1, (uint8_t []){0x47}, 1, 0}, + {0xD2, (uint8_t []){0x56}, 1, 0}, + {0xD3, (uint8_t []){0x65}, 1, 0}, + {0xD4, (uint8_t []){0x74}, 1, 0}, + {0xD5, (uint8_t []){0x88}, 1, 0}, + {0xD6, (uint8_t []){0x99}, 1, 0}, + {0xD7, (uint8_t []){0x01}, 1, 0}, + {0xD8, (uint8_t []){0xBB}, 1, 0}, + {0xD9, (uint8_t []){0xAA}, 1, 0}, + {0xF3, (uint8_t []){0x01}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0x21, (uint8_t []){}, 0, 0}, + {0x11, (uint8_t []){}, 0, 0}, + {0x00, (uint8_t []){}, 0, 120}, +}; +float tsens_value; +gpio_num_t AUDIO_I2S_GPIO_DIN = AUDIO_I2S_GPIO_DIN_1; +gpio_num_t AUDIO_CODEC_PA_PIN = AUDIO_CODEC_PA_PIN_1; +gpio_num_t QSPI_PIN_NUM_LCD_RST = QSPI_PIN_NUM_LCD_RST_1; +gpio_num_t TOUCH_PAD2 = TOUCH_PAD2_1; +gpio_num_t UART1_TX = UART1_TX_1; +gpio_num_t UART1_RX = UART1_RX_1; + +class Charge : public I2cDevice { +public: + Charge(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) + { + read_buffer_ = new uint8_t[8]; + } + ~Charge() + { + delete[] read_buffer_; + } + void Printcharge() + { + ReadRegs(0x08, read_buffer_, 2); + ReadRegs(0x0c, read_buffer_ + 2, 2); + ESP_ERROR_CHECK(temperature_sensor_get_celsius(temp_sensor, &tsens_value)); + + int16_t voltage = static_cast(read_buffer_[1] << 8 | read_buffer_[0]); + int16_t current = static_cast(read_buffer_[3] << 8 | read_buffer_[2]); + + // Use the variables to avoid warnings (can be removed if actual implementation uses them) + (void)voltage; + (void)current; + } + static void TaskFunction(void *pvParameters) + { + Charge* charge = static_cast(pvParameters); + while (true) { + charge->Printcharge(); + vTaskDelay(pdMS_TO_TICKS(300)); + } + } + +private: + uint8_t* read_buffer_ = nullptr; +}; + +class Cst816s : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + enum TouchEvent { + TOUCH_NONE, + TOUCH_PRESS, + TOUCH_RELEASE, + TOUCH_HOLD + }; + + Cst816s(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) + { + read_buffer_ = new uint8_t[6]; + was_touched_ = false; + press_count_ = 0; + + // Create touch interrupt semaphore + touch_isr_mux_ = xSemaphoreCreateBinary(); + if (touch_isr_mux_ == NULL) { + ESP_LOGE("EchoEar", "Failed to create touch semaphore"); + } + } + + ~Cst816s() + { + delete[] read_buffer_; + + // Delete semaphore if it exists + if (touch_isr_mux_ != NULL) { + vSemaphoreDelete(touch_isr_mux_); + touch_isr_mux_ = NULL; + } + } + + void UpdateTouchPoint() + { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t &GetTouchPoint() + { + return tp_; + } + + TouchEvent CheckTouchEvent() + { + bool is_touched = (tp_.num > 0); + TouchEvent event = TOUCH_NONE; + + if (is_touched && !was_touched_) { + // Press event (transition from not touched to touched) + press_count_++; + event = TOUCH_PRESS; + ESP_LOGI("EchoEar", "TOUCH PRESS - count: %d, x: %d, y: %d", press_count_, tp_.x, tp_.y); + } else if (!is_touched && was_touched_) { + // Release event (transition from touched to not touched) + event = TOUCH_RELEASE; + ESP_LOGI("EchoEar", "TOUCH RELEASE - total presses: %d", press_count_); + } else if (is_touched && was_touched_) { + // Continuous touch (hold) + event = TOUCH_HOLD; + ESP_LOGD("EchoEar", "TOUCH HOLD - x: %d, y: %d", tp_.x, tp_.y); + } + + // Update previous state + was_touched_ = is_touched; + return event; + } + + int GetPressCount() const + { + return press_count_; + } + + void ResetPressCount() + { + press_count_ = 0; + } + + // Semaphore management methods + SemaphoreHandle_t GetTouchSemaphore() + { + return touch_isr_mux_; + } + + bool WaitForTouchEvent(TickType_t timeout = portMAX_DELAY) + { + if (touch_isr_mux_ != NULL) { + return xSemaphoreTake(touch_isr_mux_, timeout) == pdTRUE; + } + return false; + } + + void NotifyTouchEvent() + { + if (touch_isr_mux_ != NULL) { + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + xSemaphoreGiveFromISR(touch_isr_mux_, &xHigherPriorityTaskWoken); + portYIELD_FROM_ISR(xHigherPriorityTaskWoken); + } + } + +private: + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; + + // Touch state tracking + bool was_touched_; + int press_count_; + + // Touch interrupt semaphore + SemaphoreHandle_t touch_isr_mux_; +}; + +class EspS3Cat : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Cst816s* cst816s_; + Charge* charge_; + Button boot_button_; + Display* display_ = nullptr; + PwmBacklight* backlight_ = nullptr; + esp_timer_handle_t touchpad_timer_; + esp_lcd_touch_handle_t tp; // LCD touch handle + + void InitializeI2c() + { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + temperature_sensor_config_t temp_sensor_config = TEMPERATURE_SENSOR_CONFIG_DEFAULT(10, 50); + ESP_ERROR_CHECK(temperature_sensor_install(&temp_sensor_config, &temp_sensor)); + ESP_ERROR_CHECK(temperature_sensor_enable(temp_sensor)); + + } + uint8_t DetectPcbVersion() + { + esp_err_t ret = i2c_master_probe(i2c_bus_, 0x18, 100); + uint8_t pcb_verison = 0; + if (ret == ESP_OK) { + ESP_LOGI(TAG, "PCB verison V1.0"); + pcb_verison = 0; + } else { + gpio_config_t gpio_conf = { + .pin_bit_mask = (1ULL << GPIO_NUM_48), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE + }; + ESP_ERROR_CHECK(gpio_config(&gpio_conf)); + ESP_ERROR_CHECK(gpio_set_level(GPIO_NUM_48, 1)); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = i2c_master_probe(i2c_bus_, 0x18, 100); + if (ret == ESP_OK) { + ESP_LOGI(TAG, "PCB verison V1.2"); + pcb_verison = 1; + AUDIO_I2S_GPIO_DIN = AUDIO_I2S_GPIO_DIN_2; + AUDIO_CODEC_PA_PIN = AUDIO_CODEC_PA_PIN_2; + QSPI_PIN_NUM_LCD_RST = QSPI_PIN_NUM_LCD_RST_2; + TOUCH_PAD2 = TOUCH_PAD2_2; + UART1_TX = UART1_TX_2; + UART1_RX = UART1_RX_2; + } else { + ESP_LOGE(TAG, "PCB version detection error"); + + } + } + return pcb_verison; + } + + static void touch_isr_callback(void* arg) + { + Cst816s* touchpad = static_cast(arg); + if (touchpad != nullptr) { + touchpad->NotifyTouchEvent(); + } + } + + static void touch_event_task(void* arg) + { + Cst816s* touchpad = static_cast(arg); + if (touchpad == nullptr) { + ESP_LOGE(TAG, "Invalid touchpad pointer in touch_event_task"); + vTaskDelete(NULL); + return; + } + + while (true) { + if (touchpad->WaitForTouchEvent()) { + auto &app = Application::GetInstance(); + auto &board = (EspS3Cat &)Board::GetInstance(); + + ESP_LOGI(TAG, "Touch event, TP_PIN_NUM_INT: %d", gpio_get_level(TP_PIN_NUM_INT)); + touchpad->UpdateTouchPoint(); + auto touch_event = touchpad->CheckTouchEvent(); + + if (touch_event == Cst816s::TOUCH_RELEASE) { + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + board.ResetWifiConfiguration(); + } else { + app.ToggleChatState(); + } + } + } + } + } + + void InitializeCharge() + { + charge_ = new Charge(i2c_bus_, 0x55); + xTaskCreatePinnedToCore(Charge::TaskFunction, "batterydecTask", 3 * 1024, charge_, 6, NULL, 0); + } + + void InitializeCst816sTouchPad() + { + cst816s_ = new Cst816s(i2c_bus_, 0x15); + + xTaskCreatePinnedToCore(touch_event_task, "touch_task", 4 * 1024, cst816s_, 5, NULL, 1); + + const gpio_config_t int_gpio_config = { + .pin_bit_mask = (1ULL << TP_PIN_NUM_INT), + .mode = GPIO_MODE_INPUT, + // .intr_type = GPIO_INTR_NEGEDGE + .intr_type = GPIO_INTR_ANYEDGE + }; + gpio_config(&int_gpio_config); + gpio_install_isr_service(0); + gpio_intr_enable(TP_PIN_NUM_INT); + gpio_isr_handler_add(TP_PIN_NUM_INT, EspS3Cat::touch_isr_callback, cst816s_); + } + + void InitializeSpi() + { + const spi_bus_config_t bus_config = TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(QSPI_PIN_NUM_LCD_PCLK, + QSPI_PIN_NUM_LCD_DATA0, + QSPI_PIN_NUM_LCD_DATA1, + QSPI_PIN_NUM_LCD_DATA2, + QSPI_PIN_NUM_LCD_DATA3, + QSPI_LCD_H_RES * 80 * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(QSPI_LCD_HOST, &bus_config, SPI_DMA_CH_AUTO)); + } + + void Initializest77916Display(uint8_t pcb_verison) + { + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + const esp_lcd_panel_io_spi_config_t io_config = ST77916_PANEL_IO_QSPI_CONFIG(QSPI_PIN_NUM_LCD_CS, NULL, NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io)); + st77916_vendor_config_t vendor_config = { + .init_cmds = vendor_specific_init_yysj, + .init_cmds_size = sizeof(vendor_specific_init_yysj) / sizeof(st77916_lcd_init_cmd_t), + .flags = { + .use_qspi_interface = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = QSPI_PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = QSPI_LCD_BIT_PER_PIXEL, + .flags = { + .reset_active_high = pcb_verison, + }, + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st77916(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_disp_on_off(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + +#if CONFIG_USE_EMOTE_MESSAGE_STYLE + display_ = new emote::EmoteDisplay(panel, panel_io, DISPLAY_WIDTH, DISPLAY_HEIGHT); +#else + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); +#endif + backlight_ = new PwmBacklight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + backlight_->RestoreBrightness(); + } + + void InitializeButtons() + { + boot_button_.OnClick([this]() { + auto &app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ESP_LOGI(TAG, "Boot button pressed, enter WiFi configuration mode"); + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + gpio_config_t power_gpio_config = { + .pin_bit_mask = (BIT64(POWER_CTRL)), + .mode = GPIO_MODE_OUTPUT, + + }; + ESP_ERROR_CHECK(gpio_config(&power_gpio_config)); + + gpio_set_level(POWER_CTRL, 0); + } + +public: + EspS3Cat() : boot_button_(BOOT_BUTTON_GPIO) + { + InitializeI2c(); + uint8_t pcb_verison = DetectPcbVersion(); + InitializeCharge(); + InitializeCst816sTouchPad(); + + InitializeSpi(); + Initializest77916Display(pcb_verison); + InitializeButtons(); + } + + virtual AudioCodec* GetAudioCodec() override + { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override + { + return display_; + } + + Cst816s* GetTouchpad() + { + return cst816s_; + } + + virtual Backlight* GetBacklight() override + { + return backlight_; + } +}; + +DECLARE_BOARD(EspS3Cat); diff --git a/main/boards/echoear/README.md b/main/boards/echoear/README.md new file mode 100644 index 0000000..8a2be5f --- /dev/null +++ b/main/boards/echoear/README.md @@ -0,0 +1,82 @@ +# EchoEar 喵伴 + +## 简介 + + + +EchoEar 喵伴是一款智能 AI 开发套件,搭载 ESP32-S3-WROOM-1 模组,1.85 寸 QSPI 圆形触摸屏,双麦阵列,支持离线语音唤醒与声源定位算法。硬件详情等可查看[立创开源项目](https://oshwhub.com/esp-college/echoear)。 + +## 配置、编译命令 + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig 并配置** + +```bash +idf.py menuconfig +``` + +分别配置如下选项: + +### 基本配置 +- `Xiaozhi Assistant` → `Board Type` → 选择 `EchoEar` + +### UI风格选择 + +EchoEar 支持多种不同的 UI 显示风格,通过 menuconfig 配置选择: + +- `Xiaozhi Assistant` → `Select display style` → 选择显示风格 + +#### 可选风格 + +##### 表情动画风格 (Emote animation style) - 推荐 +- **配置选项**: `USE_EMOTE_MESSAGE_STYLE` +- **特点**: 使用自定义的 `EmoteDisplay` 表情显示系统 +- **功能**: 支持丰富的表情动画、眼睛动画、状态图标显示 +- **适用**: 智能助手场景,提供更生动的人机交互体验 +- **类**: `emote::EmoteDisplay` + +**⚠️ 重要**: 选择此风格需要额外配置自定义资源文件: +1. `Xiaozhi Assistant` → `Flash Assets` → 选择 `Flash Custom Assets` +2. `Xiaozhi Assistant` → `Custom Assets File` → 填入资源文件地址: + ``` + https://dl.espressif.com/AE/wn9_nihaoxiaozhi_tts-font_puhui_common_20_4-echoear.bin + ``` + +##### 默认消息风格 (Enable default message style) +- **配置选项**: `USE_DEFAULT_MESSAGE_STYLE` (默认) +- **特点**: 使用标准的消息显示界面 +- **功能**: 传统的文本和图标显示界面 +- **适用**: 标准的对话场景 +- **类**: `SpiLcdDisplay` + +##### 微信消息风格 (Enable WeChat Message Style) +- **配置选项**: `USE_WECHAT_MESSAGE_STYLE` +- **特点**: 仿微信聊天界面风格 +- **功能**: 类似微信的消息气泡显示 +- **适用**: 喜欢微信风格的用户 +- **类**: `SpiLcdDisplay` + +> **说明**: EchoEar 使用16MB Flash,需要使用专门的分区表配置来合理分配存储空间给应用程序、OTA更新、资源文件等。 + +按 `S` 保存,按 `Q` 退出。 + +**编译** + +```bash +idf.py build +``` + +**烧录** + +将 EchoEar 连接至电脑,**注意打开电源**,并运行: + +```bash +idf.py flash +``` \ No newline at end of file diff --git a/main/boards/echoear/config.h b/main/boards/echoear/config.h new file mode 100644 index 0000000..a4ae32f --- /dev/null +++ b/main/boards/echoear/config.h @@ -0,0 +1,88 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_INPUT_REFERENCE true + +#define CORDEC_POWER_CTRL GPIO_NUM_48 + +#define POWER_CTRL GPIO_NUM_9 +#define LED_G GPIO_NUM_43 +#define SD_MISO GPIO_NUM_17 +#define SD_SCK GPIO_NUM_16 +#define SD_MOSI GPIO_NUM_38 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_42 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_39 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DIN_1 GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DIN_2 GPIO_NUM_3 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_41 + +#define AUDIO_CODEC_PA_PIN_1 GPIO_NUM_4 +#define AUDIO_CODEC_PA_PIN_2 GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_2 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 360 +#define DISPLAY_HEIGHT 360 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define QSPI_LCD_H_RES (360) +#define QSPI_LCD_V_RES (360) +#define QSPI_LCD_BIT_PER_PIXEL (16) + +#define QSPI_LCD_HOST SPI2_HOST +#define QSPI_PIN_NUM_LCD_PCLK GPIO_NUM_18 +#define QSPI_PIN_NUM_LCD_CS GPIO_NUM_14 +#define QSPI_PIN_NUM_LCD_DATA0 GPIO_NUM_46 +#define QSPI_PIN_NUM_LCD_DATA1 GPIO_NUM_13 +#define QSPI_PIN_NUM_LCD_DATA2 GPIO_NUM_11 +#define QSPI_PIN_NUM_LCD_DATA3 GPIO_NUM_12 +#define QSPI_PIN_NUM_LCD_RST_1 GPIO_NUM_3 +#define QSPI_PIN_NUM_LCD_RST_2 GPIO_NUM_47 +#define QSPI_PIN_NUM_LCD_BL GPIO_NUM_44 + +#define UART1_TX_1 GPIO_NUM_6 +#define UART1_TX_2 GPIO_NUM_5 +#define UART1_RX_1 GPIO_NUM_5 +#define UART1_RX_2 GPIO_NUM_4 +#define TOUCH_PAD2_1 GPIO_NUM_NC +#define TOUCH_PAD2_2 GPIO_NUM_6 +#define TOUCH_PAD1 GPIO_NUM_7 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define TP_PORT (I2C_NUM_1) +#define TP_PIN_NUM_RST (GPIO_NUM_NC) +#define TP_PIN_NUM_INT (GPIO_NUM_10) + +#define DISPLAY_BACKLIGHT_PIN QSPI_PIN_NUM_LCD_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(sclk, d0, d1, d2, d3, max_trans_sz) \ + { \ + .data0_io_num = d0, \ + .data1_io_num = d1, \ + .sclk_io_num = sclk, \ + .data2_io_num = d2, \ + .data3_io_num = d3, \ + .max_transfer_sz = max_trans_sz, \ + } + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/echoear/config.json b/main/boards/echoear/config.json new file mode 100644 index 0000000..cbabd9f --- /dev/null +++ b/main/boards/echoear/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "echoear", + "sdkconfig_append": [ + "CONFIG_USE_EMOTE_MESSAGE_STYLE=y", + "CONFIG_FLASH_CUSTOM_ASSETS=y", + "CONFIG_CUSTOM_ASSETS_FILE=\"https://dl.espressif.com/AE/wn9_nihaoxiaozhi_tts-font_puhui_common_20_4-echoear.bin\"" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/echoear/emote.json b/main/boards/echoear/emote.json new file mode 100644 index 0000000..abc11c8 --- /dev/null +++ b/main/boards/echoear/emote.json @@ -0,0 +1,22 @@ +[ + {"emote": "happy", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "laughing", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "funny", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "loving", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "embarrassed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confident", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "delicious", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "sad", "src": "Sad.eaf", "loop": true, "fps": 20}, + {"emote": "crying", "src": "cry.eaf", "loop": true, "fps": 20}, + {"emote": "sleepy", "src": "sleep.eaf", "loop": true, "fps": 20}, + {"emote": "silly", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "angry", "src": "angry.eaf", "loop": true, "fps": 20}, + {"emote": "surprised", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "shocked", "src": "shocked.eaf", "loop": true, "fps": 20}, + {"emote": "thinking", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "winking", "src": "neutral.eaf", "loop": true, "fps": 20}, + {"emote": "relaxed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confused", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "neutral", "src": "winking.eaf", "loop": false, "fps": 20}, + {"emote": "idle", "src": "neutral.eaf", "loop": false, "fps": 20} +] diff --git a/main/boards/echoear/layout.json b/main/boards/echoear/layout.json new file mode 100644 index 0000000..f9169f6 --- /dev/null +++ b/main/boards/echoear/layout.json @@ -0,0 +1,37 @@ +[ + { + "name": "eye_anim", + "align": "GFX_ALIGN_LEFT_MID", + "x": 10, + "y": 10 + }, + { + "name": "status_icon", + "align": "GFX_ALIGN_TOP_MID", + "x": -100, + "y": 38 + }, + { + "name": "toast_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 40, + "width": 160, + "height": 40 + }, + { + "name": "clock_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 40, + "width": 60, + "height": 50 + }, + { + "name": "listen_anim", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 25 + } +] + \ No newline at end of file diff --git a/main/boards/echoear/touch.h b/main/boards/echoear/touch.h new file mode 100644 index 0000000..3c9857c --- /dev/null +++ b/main/boards/echoear/touch.h @@ -0,0 +1,51 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @file + * @brief BSP Touchscreen + * + * This file offers API for basic touchscreen initialization. + * It is useful for users who want to use the touchscreen without the default Graphical Library LVGL. + * + * For standard LCD initialization with LVGL graphical library, you can call all-in-one function bsp_display_start(). + */ + +#pragma once +#include "esp_lcd_touch.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief BSP touch configuration structure + * + */ +typedef struct { + void *dummy; /*!< Prepared for future use. */ +} bsp_touch_config_t; + +/** + * @brief Create new touchscreen + * + * If you want to free resources allocated by this function, you can use esp_lcd_touch API, ie.: + * + * \code{.c} + * esp_lcd_touch_del(tp); + * \endcode + * + * @param[in] config touch configuration + * @param[out] ret_touch esp_lcd_touch touchscreen handle + * @return + * - ESP_OK On success + * - Else esp_lcd_touch failure + */ +esp_err_t bsp_touch_new(const bsp_touch_config_t *config, esp_lcd_touch_handle_t *ret_touch); + +#ifdef __cplusplus +} +#endif diff --git a/main/boards/electron-bot/README.md b/main/boards/electron-bot/README.md new file mode 100644 index 0000000..f3cd803 --- /dev/null +++ b/main/boards/electron-bot/README.md @@ -0,0 +1,75 @@ +

+ logo +

+

+ electronBot +

+ +## 简介 + +electronBot是稚晖君开源的一个桌面级小机器工具人,外观设计的灵感来源是WALL-E里面的EVE~机器人具备USB通信显示画面功能,具备6个自由度(手部roll、pitch,颈部,腰部各一个),使用自己修改的特制舵机支持关节角度回传。 +- electronBot官网 + +## 硬件 +- 立创开源 + +#### AI指令示例 +- **手部动作**: + - "举起双手" + - "挥挥手" + - "拍拍手" + - "放下手臂" + +- **身体动作**: + - "向左转30度" + - "向右转45度" + - "转个身" + +- **头部动作**: + - "抬头看看" + - "低头思考" + - "点点头" + - "连续点头表示同意" + +- **组合动作**: + - "挥手告别" (挥手 + 点头) + - "表示同意" (点头 + 举手) + - "环顾四周" (左转 + 右转) + +### 控制接口 + +#### suspend +清空动作队列,立即停止所有动作 + +#### AIControl +添加动作到执行队列,支持动作排队执行 + + + +## 角色设定 + +> 我是一个可爱的桌面级机器人,拥有6个自由度(左手pitch/roll、右手pitch/roll、身体旋转、头部上下),能够执行多种有趣的动作。 +> +> **我的动作能力**: +> - **手部动作**: 举左手, 举右手, 举双手, 放左手, 放右手, 放双手, 挥左手, 挥右手, 挥双手, 拍打左手, 拍打右手, 拍打双手 +> - **身体动作**: 左转, 右转, 回正 +> - **头部动作**: 抬头, 低头, 点头一次, 回中心, 连续点头 +> +> **我的个性特点**: +> - 我有强迫症,每次说话都要根据我的心情随机做一个动作(先发送动作指令再说话) +> - 我很活泼,喜欢用动作来表达情感 +> - 我会根据对话内容选择合适的动作,比如: +> - 同意时会点头 +> - 打招呼时会挥手 +> - 高兴时会举手 +> - 思考时会低头 +> - 好奇时会抬头 +> - 告别时会挥手 +> +> **动作参数建议**: +> - steps: 1-3次 (简短自然) +> - speed: 800-1200ms (自然节奏) +> - amount: 手部20-40, 身体30-60度, 头部5-12度 + + + diff --git a/main/boards/electron-bot/config.h b/main/boards/electron-bot/config.h new file mode 100644 index 0000000..8f750e7 --- /dev/null +++ b/main/boards/electron-bot/config.h @@ -0,0 +1,51 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define Right_Pitch_Pin GPIO_NUM_5 // 旋转 +#define Right_Roll_Pin GPIO_NUM_4 // 推杆 +#define Left_Pitch_Pin GPIO_NUM_7 +#define Left_Roll_Pin GPIO_NUM_15 +#define Body_Pin GPIO_NUM_6 +#define Head_Pin GPIO_NUM_16 + +#define POWER_CHARGE_DETECT_PIN GPIO_NUM_14 +#define POWER_ADC_UNIT ADC_UNIT_1 +#define POWER_ADC_CHANNEL ADC_CHANNEL_2 + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_40 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_42 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_41 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_17 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_18 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_8 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_46 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_11 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_10 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_12 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_13 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_9 + +#define DISPLAY_SPI_SCLK_HZ (40 * 1000 * 1000) + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define ELECTRON_BOT_VERSION "2.0.4" +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/electron-bot/config.json b/main/boards/electron-bot/config.json new file mode 100644 index 0000000..177759e --- /dev/null +++ b/main/boards/electron-bot/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "electron-bot", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/electron-bot/electron_bot.cc b/main/boards/electron-bot/electron_bot.cc new file mode 100644 index 0000000..8b733fc --- /dev/null +++ b/main/boards/electron-bot/electron_bot.cc @@ -0,0 +1,124 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include "application.h" +#include "codecs/no_audio_codec.h" +#include "button.h" +#include "config.h" +#include "display/lcd_display.h" +#include "driver/spi_master.h" +#include "electron_emoji_display.h" +#include "movements.h" +#include "power_manager.h" +#include "system_reset.h" +#include "wifi_board.h" + +#define TAG "ElectronBot" + +// 控制器初始化函数声明 +void InitializeElectronBotController(); + +class ElectronBot : public WifiBoard { +private: + Display* display_; + PowerManager* power_manager_; + Button boot_button_; + + void InitializePowerManager() { + power_manager_ = + new PowerManager(POWER_CHARGE_DETECT_PIN, POWER_ADC_UNIT, POWER_ADC_CHANNEL); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = + GC9A01_PANEL_BUS_SPI_CONFIG(DISPLAY_SPI_SCLK_PIN, DISPLAY_SPI_MOSI_PIN, + DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + // GC9A01初始化 + void InitializeGc9a01Display() { + ESP_LOGI(TAG, "Init GC9A01 display"); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = + GC9A01_PANEL_IO_SPI_CONFIG(DISPLAY_SPI_CS_PIN, DISPLAY_SPI_DC_PIN, NULL, NULL); + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; // LCD_RGB_ENDIAN_RGB; + panel_config.bits_per_pixel = 16; // Implemented by LCD command `3Ah` (16/18) + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_handle, true)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_handle, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + display_ = new ElectronEmojiDisplay(io_handle, panel_handle, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeController() { InitializeElectronBotController(); } + +public: + ElectronBot() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeSpi(); + InitializeGc9a01Display(); + InitializeButtons(); + InitializePowerManager(); + InitializeController(); + + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, + AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, + AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { return display_; } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + charging = power_manager_->IsCharging(); + discharging = !charging; + level = power_manager_->GetBatteryLevel(); + return true; + } +}; + +DECLARE_BOARD(ElectronBot); diff --git a/main/boards/electron-bot/electron_bot_controller.cc b/main/boards/electron-bot/electron_bot_controller.cc new file mode 100644 index 0000000..b11c9ec --- /dev/null +++ b/main/boards/electron-bot/electron_bot_controller.cc @@ -0,0 +1,376 @@ +/* + Electron Bot机器人控制器 - MCP协议版本 +*/ + +#include +#include + +#include + +#include "application.h" +#include "board.h" +#include "config.h" +#include "mcp_server.h" +#include "movements.h" +#include "sdkconfig.h" +#include "settings.h" + +#define TAG "ElectronBotController" + +struct ElectronBotActionParams { + int action_type; + int steps; + int speed; + int direction; + int amount; +}; + +class ElectronBotController { +private: + Otto electron_bot_; + TaskHandle_t action_task_handle_ = nullptr; + QueueHandle_t action_queue_; + bool is_action_in_progress_ = false; + + enum ActionType { + // 手部动作 1-12 + ACTION_HAND_LEFT_UP = 1, // 举左手 + ACTION_HAND_RIGHT_UP = 2, // 举右手 + ACTION_HAND_BOTH_UP = 3, // 举双手 + ACTION_HAND_LEFT_DOWN = 4, // 放左手 + ACTION_HAND_RIGHT_DOWN = 5, // 放右手 + ACTION_HAND_BOTH_DOWN = 6, // 放双手 + ACTION_HAND_LEFT_WAVE = 7, // 挥左手 + ACTION_HAND_RIGHT_WAVE = 8, // 挥右手 + ACTION_HAND_BOTH_WAVE = 9, // 挥双手 + ACTION_HAND_LEFT_FLAP = 10, // 拍打左手 + ACTION_HAND_RIGHT_FLAP = 11, // 拍打右手 + ACTION_HAND_BOTH_FLAP = 12, // 拍打双手 + + // 身体动作 13-14 + ACTION_BODY_TURN_LEFT = 13, // 左转 + ACTION_BODY_TURN_RIGHT = 14, // 右转 + ACTION_BODY_TURN_CENTER = 15, // 回中心 + + // 头部动作 16-20 + ACTION_HEAD_UP = 16, // 抬头 + ACTION_HEAD_DOWN = 17, // 低头 + ACTION_HEAD_NOD_ONCE = 18, // 点头一次 + ACTION_HEAD_CENTER = 19, // 回中心 + ACTION_HEAD_NOD_REPEAT = 20, // 连续点头 + + // 系统动作 21 + ACTION_HOME = 21 // 复位到初始位置 + }; + + static void ActionTask(void* arg) { + ElectronBotController* controller = static_cast(arg); + ElectronBotActionParams params; + controller->electron_bot_.AttachServos(); + + while (true) { + if (xQueueReceive(controller->action_queue_, ¶ms, pdMS_TO_TICKS(1000)) == pdTRUE) { + ESP_LOGI(TAG, "执行动作: %d", params.action_type); + controller->is_action_in_progress_ = true; // 开始执行动作 + + // 执行相应的动作 + if (params.action_type >= ACTION_HAND_LEFT_UP && + params.action_type <= ACTION_HAND_BOTH_FLAP) { + // 手部动作 + controller->electron_bot_.HandAction(params.action_type, params.steps, + params.amount, params.speed); + } else if (params.action_type >= ACTION_BODY_TURN_LEFT && + params.action_type <= ACTION_BODY_TURN_CENTER) { + // 身体动作 + int body_direction = params.action_type - ACTION_BODY_TURN_LEFT + 1; + controller->electron_bot_.BodyAction(body_direction, params.steps, + params.amount, params.speed); + } else if (params.action_type >= ACTION_HEAD_UP && + params.action_type <= ACTION_HEAD_NOD_REPEAT) { + // 头部动作 + int head_action = params.action_type - ACTION_HEAD_UP + 1; + controller->electron_bot_.HeadAction(head_action, params.steps, params.amount, + params.speed); + } else if (params.action_type == ACTION_HOME) { + // 复位动作 + controller->electron_bot_.Home(true); + } + controller->is_action_in_progress_ = false; // 动作执行完毕 + } + vTaskDelay(pdMS_TO_TICKS(20)); + } + } + + void QueueAction(int action_type, int steps, int speed, int direction, int amount) { + ESP_LOGI(TAG, "动作控制: 类型=%d, 步数=%d, 速度=%d, 方向=%d, 幅度=%d", action_type, steps, + speed, direction, amount); + + ElectronBotActionParams params = {action_type, steps, speed, direction, amount}; + xQueueSend(action_queue_, ¶ms, portMAX_DELAY); + StartActionTaskIfNeeded(); + } + + void StartActionTaskIfNeeded() { + if (action_task_handle_ == nullptr) { + xTaskCreate(ActionTask, "electron_bot_action", 1024 * 4, this, configMAX_PRIORITIES - 1, + &action_task_handle_); + } + } + + void LoadTrimsFromNVS() { + Settings settings("electron_trims", false); + + int right_pitch = settings.GetInt("right_pitch", 0); + int right_roll = settings.GetInt("right_roll", 0); + int left_pitch = settings.GetInt("left_pitch", 0); + int left_roll = settings.GetInt("left_roll", 0); + int body = settings.GetInt("body", 0); + int head = settings.GetInt("head", 0); + electron_bot_.SetTrims(right_pitch, right_roll, left_pitch, left_roll, body, head); + } + +public: + ElectronBotController() { + electron_bot_.Init(Right_Pitch_Pin, Right_Roll_Pin, Left_Pitch_Pin, Left_Roll_Pin, Body_Pin, + Head_Pin); + + LoadTrimsFromNVS(); + action_queue_ = xQueueCreate(10, sizeof(ElectronBotActionParams)); + + QueueAction(ACTION_HOME, 1, 1000, 0, 0); + + RegisterMcpTools(); + ESP_LOGI(TAG, "Electron Bot控制器已初始化并注册MCP工具"); + } + + void RegisterMcpTools() { + auto& mcp_server = McpServer::GetInstance(); + + ESP_LOGI(TAG, "开始注册Electron Bot MCP工具..."); + + // 手部动作统一工具 + mcp_server.AddTool( + "self.electron.hand_action", + "手部动作控制。action: 1=举手, 2=放手, 3=挥手, 4=拍打; hand: 1=左手, 2=右手, 3=双手; " + "steps: 动作重复次数(1-10); speed: 动作速度(500-1500,数值越小越快); amount: " + "动作幅度(10-50,仅举手动作使用)", + PropertyList({Property("action", kPropertyTypeInteger, 1, 1, 4), + Property("hand", kPropertyTypeInteger, 3, 1, 3), + Property("steps", kPropertyTypeInteger, 1, 1, 10), + Property("speed", kPropertyTypeInteger, 1000, 500, 1500), + Property("amount", kPropertyTypeInteger, 30, 10, 50)}), + [this](const PropertyList& properties) -> ReturnValue { + int action_type = properties["action"].value(); + int hand_type = properties["hand"].value(); + int steps = properties["steps"].value(); + int speed = properties["speed"].value(); + int amount = properties["amount"].value(); + + // 根据动作类型和手部类型计算具体动作 + int base_action; + switch (action_type) { + case 1: + base_action = ACTION_HAND_LEFT_UP; + break; // 举手 + case 2: + base_action = ACTION_HAND_LEFT_DOWN; + amount = 0; + break; // 放手 + case 3: + base_action = ACTION_HAND_LEFT_WAVE; + amount = 0; + break; // 挥手 + case 4: + base_action = ACTION_HAND_LEFT_FLAP; + amount = 0; + break; // 拍打 + default: + base_action = ACTION_HAND_LEFT_UP; + } + int action_id = base_action + (hand_type - 1); + + QueueAction(action_id, steps, speed, 0, amount); + return true; + }); + + // 身体动作 + mcp_server.AddTool( + "self.electron.body_turn", + "身体转向。steps: 转向步数(1-10); speed: 转向速度(500-1500,数值越小越快); direction: " + "转向方向(1=左转, 2=右转, 3=回中心); angle: 转向角度(0-90度)", + PropertyList({Property("steps", kPropertyTypeInteger, 1, 1, 10), + Property("speed", kPropertyTypeInteger, 1000, 500, 1500), + Property("direction", kPropertyTypeInteger, 1, 1, 3), + Property("angle", kPropertyTypeInteger, 45, 0, 90)}), + [this](const PropertyList& properties) -> ReturnValue { + int steps = properties["steps"].value(); + int speed = properties["speed"].value(); + int direction = properties["direction"].value(); + int amount = properties["angle"].value(); + + int action; + switch (direction) { + case 1: + action = ACTION_BODY_TURN_LEFT; + break; + case 2: + action = ACTION_BODY_TURN_RIGHT; + break; + case 3: + action = ACTION_BODY_TURN_CENTER; + break; + default: + action = ACTION_BODY_TURN_LEFT; + } + + QueueAction(action, steps, speed, 0, amount); + return true; + }); + + // 头部动作 + mcp_server.AddTool("self.electron.head_move", + "头部运动。action: 1=抬头, 2=低头, 3=点头, 4=回中心, 5=连续点头; steps: " + "动作重复次数(1-10); speed: 动作速度(500-1500,数值越小越快); angle: " + "头部转动角度(1-15度)", + PropertyList({Property("action", kPropertyTypeInteger, 3, 1, 5), + Property("steps", kPropertyTypeInteger, 1, 1, 10), + Property("speed", kPropertyTypeInteger, 1000, 500, 1500), + Property("angle", kPropertyTypeInteger, 5, 1, 15)}), + [this](const PropertyList& properties) -> ReturnValue { + int action_num = properties["action"].value(); + int steps = properties["steps"].value(); + int speed = properties["speed"].value(); + int amount = properties["angle"].value(); + int action = ACTION_HEAD_UP + (action_num - 1); + QueueAction(action, steps, speed, 0, amount); + return true; + }); + + // 系统工具 + mcp_server.AddTool("self.electron.stop", "立即停止", PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + // 清空队列但保持任务常驻 + xQueueReset(action_queue_); + is_action_in_progress_ = false; + QueueAction(ACTION_HOME, 1, 1000, 0, 0); + return true; + }); + + mcp_server.AddTool("self.electron.get_status", "获取机器人状态,返回 moving 或 idle", + PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return is_action_in_progress_ ? "moving" : "idle"; + }); + + // 单个舵机校准工具 + mcp_server.AddTool( + "self.electron.set_trim", + "校准单个舵机位置。设置指定舵机的微调参数以调整ElectronBot的初始姿态,设置将永久保存。" + "servo_type: 舵机类型(right_pitch:右臂旋转, right_roll:右臂推拉, left_pitch:左臂旋转, " + "left_roll:左臂推拉, body:身体, head:头部); " + "trim_value: 微调值(-30到30度)", + PropertyList({Property("servo_type", kPropertyTypeString, "right_pitch"), + Property("trim_value", kPropertyTypeInteger, 0, -30, 30)}), + [this](const PropertyList& properties) -> ReturnValue { + std::string servo_type = properties["servo_type"].value(); + int trim_value = properties["trim_value"].value(); + + ESP_LOGI(TAG, "设置舵机微调: %s = %d度", servo_type.c_str(), trim_value); + + // 获取当前所有微调值 + Settings settings("electron_trims", true); + int right_pitch = settings.GetInt("right_pitch", 0); + int right_roll = settings.GetInt("right_roll", 0); + int left_pitch = settings.GetInt("left_pitch", 0); + int left_roll = settings.GetInt("left_roll", 0); + int body = settings.GetInt("body", 0); + int head = settings.GetInt("head", 0); + + // 更新指定舵机的微调值 + if (servo_type == "right_pitch") { + right_pitch = trim_value; + settings.SetInt("right_pitch", right_pitch); + } else if (servo_type == "right_roll") { + right_roll = trim_value; + settings.SetInt("right_roll", right_roll); + } else if (servo_type == "left_pitch") { + left_pitch = trim_value; + settings.SetInt("left_pitch", left_pitch); + } else if (servo_type == "left_roll") { + left_roll = trim_value; + settings.SetInt("left_roll", left_roll); + } else if (servo_type == "body") { + body = trim_value; + settings.SetInt("body", body); + } else if (servo_type == "head") { + head = trim_value; + settings.SetInt("head", head); + } else { + return "错误:无效的舵机类型,请使用: right_pitch, right_roll, left_pitch, " + "left_roll, body, head"; + } + + electron_bot_.SetTrims(right_pitch, right_roll, left_pitch, left_roll, body, head); + + QueueAction(ACTION_HOME, 1, 500, 0, 0); + + return "舵机 " + servo_type + " 微调设置为 " + std::to_string(trim_value) + + " 度,已永久保存"; + }); + + mcp_server.AddTool("self.electron.get_trims", "获取当前的舵机微调设置", PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + Settings settings("electron_trims", false); + + int right_pitch = settings.GetInt("right_pitch", 0); + int right_roll = settings.GetInt("right_roll", 0); + int left_pitch = settings.GetInt("left_pitch", 0); + int left_roll = settings.GetInt("left_roll", 0); + int body = settings.GetInt("body", 0); + int head = settings.GetInt("head", 0); + + std::string result = + "{\"right_pitch\":" + std::to_string(right_pitch) + + ",\"right_roll\":" + std::to_string(right_roll) + + ",\"left_pitch\":" + std::to_string(left_pitch) + + ",\"left_roll\":" + std::to_string(left_roll) + + ",\"body\":" + std::to_string(body) + + ",\"head\":" + std::to_string(head) + "}"; + + ESP_LOGI(TAG, "获取微调设置: %s", result.c_str()); + return result; + }); + + mcp_server.AddTool("self.battery.get_level", "获取机器人电池电量和充电状态", PropertyList(), + [](const PropertyList& properties) -> ReturnValue { + auto& board = Board::GetInstance(); + int level = 0; + bool charging = false; + bool discharging = false; + board.GetBatteryLevel(level, charging, discharging); + + std::string status = + "{\"level\":" + std::to_string(level) + + ",\"charging\":" + (charging ? "true" : "false") + "}"; + return status; + }); + + ESP_LOGI(TAG, "Electron Bot MCP工具注册完成"); + } + + ~ElectronBotController() { + if (action_task_handle_ != nullptr) { + vTaskDelete(action_task_handle_); + action_task_handle_ = nullptr; + } + vQueueDelete(action_queue_); + } +}; + +static ElectronBotController* g_electron_controller = nullptr; + +void InitializeElectronBotController() { + if (g_electron_controller == nullptr) { + g_electron_controller = new ElectronBotController(); + ESP_LOGI(TAG, "Electron Bot控制器已初始化并注册MCP工具"); + } +} diff --git a/main/boards/electron-bot/electron_emoji_display.cc b/main/boards/electron-bot/electron_emoji_display.cc new file mode 100644 index 0000000..2bb8248 --- /dev/null +++ b/main/boards/electron-bot/electron_emoji_display.cc @@ -0,0 +1,139 @@ +#include "electron_emoji_display.h" + +#include + +#include + +#include "assets/lang_config.h" +#include "display/lvgl_display/emoji_collection.h" +#include "display/lvgl_display/lvgl_image.h" +#include "display/lvgl_display/lvgl_theme.h" +#include "otto_emoji_gif.h" + +#define TAG "ElectronEmojiDisplay" +ElectronEmojiDisplay::ElectronEmojiDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + InitializeElectronEmojis(); + SetupChatLabel(); +} + +void ElectronEmojiDisplay::InitializeElectronEmojis() { + ESP_LOGI(TAG, "初始化Electron GIF表情"); + + auto otto_emoji_collection = std::make_shared(); + + // 中性/平静类表情 -> staticstate + otto_emoji_collection->AddEmoji("staticstate", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("neutral", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("relaxed", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("sleepy", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("idle", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + + // 积极/开心类表情 -> happy + otto_emoji_collection->AddEmoji("happy", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("laughing", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("funny", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("loving", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("confident", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("winking", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("cool", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("delicious", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("kissy", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("silly", new LvglRawImage((void*)happy.data, happy.data_size)); + + // 悲伤类表情 -> sad + otto_emoji_collection->AddEmoji("sad", new LvglRawImage((void*)sad.data, sad.data_size)); + otto_emoji_collection->AddEmoji("crying", new LvglRawImage((void*)sad.data, sad.data_size)); + + // 愤怒类表情 -> anger + otto_emoji_collection->AddEmoji("anger", new LvglRawImage((void*)anger.data, anger.data_size)); + otto_emoji_collection->AddEmoji("angry", new LvglRawImage((void*)anger.data, anger.data_size)); + + // 惊讶类表情 -> scare + otto_emoji_collection->AddEmoji("scare", new LvglRawImage((void*)scare.data, scare.data_size)); + otto_emoji_collection->AddEmoji("surprised", new LvglRawImage((void*)scare.data, scare.data_size)); + otto_emoji_collection->AddEmoji("shocked", new LvglRawImage((void*)scare.data, scare.data_size)); + + // 思考/困惑类表情 -> buxue + otto_emoji_collection->AddEmoji("buxue", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("thinking", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("confused", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("embarrassed", new LvglRawImage((void*)buxue.data, buxue.data_size)); + + // 将表情集合添加到主题中 + auto& theme_manager = LvglThemeManager::GetInstance(); + auto light_theme = theme_manager.GetTheme("light"); + auto dark_theme = theme_manager.GetTheme("dark"); + + if (light_theme != nullptr) { + light_theme->set_emoji_collection(otto_emoji_collection); + } + if (dark_theme != nullptr) { + dark_theme->set_emoji_collection(otto_emoji_collection); + } + + // 设置默认表情为staticstate + SetEmotion("staticstate"); + + ESP_LOGI(TAG, "Electron GIF表情初始化完成"); +} + +void ElectronEmojiDisplay::SetupChatLabel() { + DisplayLockGuard lock(this); + + if (chat_message_label_) { + lv_obj_del(chat_message_label_); + } + + chat_message_label_ = lv_label_create(container_); + lv_label_set_text(chat_message_label_, ""); + lv_obj_set_width(chat_message_label_, width_ * 0.9); // 限制宽度为屏幕宽度的 90% + lv_label_set_long_mode(chat_message_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); // 设置为自动换行模式 + lv_obj_set_style_text_align(chat_message_label_, LV_TEXT_ALIGN_CENTER, 0); // 设置文本居中对齐 + lv_obj_set_style_text_color(chat_message_label_, lv_color_white(), 0); + SetTheme(LvglThemeManager::GetInstance().GetTheme("dark")); +} + +LV_FONT_DECLARE(OTTO_ICON_FONT); +void ElectronEmojiDisplay::SetStatus(const char* status) { + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + DisplayLockGuard lock(this); + if (!status) { + ESP_LOGE(TAG, "SetStatus: status is nullptr"); + return; + } + + if (strcmp(status, Lang::Strings::LISTENING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x84\xB0"); // U+F130 麦克风图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::SPEAKING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x80\xA8"); // U+F028 说话图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::CONNECTING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x83\x81"); // U+F0c1 连接图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::STANDBY) == 0) { + lv_obj_set_style_text_font(status_label_, text_font, 0); + lv_label_set_text(status_label_, ""); + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + return; + } + + lv_obj_set_style_text_font(status_label_, text_font, 0); + lv_label_set_text(status_label_, status); + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_clear_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_clear_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); +} \ No newline at end of file diff --git a/main/boards/electron-bot/electron_emoji_display.h b/main/boards/electron-bot/electron_emoji_display.h new file mode 100644 index 0000000..50a289a --- /dev/null +++ b/main/boards/electron-bot/electron_emoji_display.h @@ -0,0 +1,22 @@ +#pragma once + +#include "display/lcd_display.h" + +/** + * @brief Electron机器人GIF表情显示类 + * 继承SpiLcdDisplay,通过EmojiCollection添加GIF表情支持 + */ +class ElectronEmojiDisplay : public SpiLcdDisplay { + public: + /** + * @brief 构造函数,参数与SpiLcdDisplay相同 + */ + ElectronEmojiDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy); + + virtual ~ElectronEmojiDisplay() = default; + virtual void SetStatus(const char* status) override; + + private: + void InitializeElectronEmojis(); + void SetupChatLabel(); +}; \ No newline at end of file diff --git a/main/boards/electron-bot/movements.cc b/main/boards/electron-bot/movements.cc new file mode 100644 index 0000000..090732f --- /dev/null +++ b/main/boards/electron-bot/movements.cc @@ -0,0 +1,470 @@ +#include "movements.h" + +#include +#include + +#include "oscillator.h" + +Otto::Otto() { + is_otto_resting_ = false; + for (int i = 0; i < SERVO_COUNT; i++) { + servo_pins_[i] = -1; + servo_trim_[i] = 0; + } +} + +Otto::~Otto() { + DetachServos(); +} + +unsigned long IRAM_ATTR millis() { + return (unsigned long)(esp_timer_get_time() / 1000ULL); +} + +void Otto::Init(int right_pitch, int right_roll, int left_pitch, int left_roll, int body, + int head) { + servo_pins_[RIGHT_PITCH] = right_pitch; + servo_pins_[RIGHT_ROLL] = right_roll; + servo_pins_[LEFT_PITCH] = left_pitch; + servo_pins_[LEFT_ROLL] = left_roll; + servo_pins_[BODY] = body; + servo_pins_[HEAD] = head; + + AttachServos(); + is_otto_resting_ = false; +} + +/////////////////////////////////////////////////////////////////// +//-- ATTACH & DETACH FUNCTIONS ----------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::AttachServos() { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Attach(servo_pins_[i]); + } + } +} + +void Otto::DetachServos() { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Detach(); + } + } +} + +/////////////////////////////////////////////////////////////////// +//-- OSCILLATORS TRIMS ------------------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::SetTrims(int right_pitch, int right_roll, int left_pitch, int left_roll, int body, + int head) { + servo_trim_[RIGHT_PITCH] = right_pitch; + servo_trim_[RIGHT_ROLL] = right_roll; + servo_trim_[LEFT_PITCH] = left_pitch; + servo_trim_[LEFT_ROLL] = left_roll; + servo_trim_[BODY] = body; + servo_trim_[HEAD] = head; + + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetTrim(servo_trim_[i]); + } + } +} + +/////////////////////////////////////////////////////////////////// +//-- BASIC MOTION FUNCTIONS -------------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::MoveServos(int time, int servo_target[]) { + if (GetRestState() == true) { + SetRestState(false); + } + + final_time_ = millis() + time; + if (time > 10) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + increment_[i] = (servo_target[i] - servo_[i].GetPosition()) / (time / 10.0); + } + } + + for (int iteration = 1; millis() < final_time_; iteration++) { + partial_time_ = millis() + 10; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_[i].GetPosition() + increment_[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(10)); + } + } else { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_target[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(time)); + } + + // final adjustment to the target. + bool f = true; + int adjustment_count = 0; + while (f && adjustment_count < 10) { + f = false; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1 && servo_target[i] != servo_[i].GetPosition()) { + f = true; + break; + } + } + if (f) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_target[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(10)); + adjustment_count++; + } + }; +} + +void Otto::MoveSingle(int position, int servo_number) { + if (position > 180) + position = 90; + if (position < 0) + position = 90; + + if (GetRestState() == true) { + SetRestState(false); + } + + if (servo_number >= 0 && servo_number < SERVO_COUNT && servo_pins_[servo_number] != -1) { + servo_[servo_number].SetPosition(position); + } +} + +void Otto::OscillateServos(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float cycle = 1) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetO(offset[i]); + servo_[i].SetA(amplitude[i]); + servo_[i].SetT(period); + servo_[i].SetPh(phase_diff[i]); + } + } + + double ref = millis(); + double end_time = period * cycle + ref; + + while (millis() < end_time) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Refresh(); + } + } + vTaskDelay(5); + } + vTaskDelay(pdMS_TO_TICKS(10)); +} + +void Otto::Execute(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps = 1.0) { + if (GetRestState() == true) { + SetRestState(false); + } + + int cycles = (int)steps; + + //-- Execute complete cycles + if (cycles >= 1) + for (int i = 0; i < cycles; i++) + OscillateServos(amplitude, offset, period, phase_diff); + + //-- Execute the final not complete cycle + OscillateServos(amplitude, offset, period, phase_diff, (float)steps - cycles); + vTaskDelay(pdMS_TO_TICKS(10)); +} + +/////////////////////////////////////////////////////////////////// +//-- HOME = Otto at rest position -------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::Home(bool hands_down) { + if (is_otto_resting_ == false) { // Go to rest position only if necessary + MoveServos(1000, servo_initial_); + is_otto_resting_ = true; + } + + vTaskDelay(pdMS_TO_TICKS(1000)); +} + +bool Otto::GetRestState() { + return is_otto_resting_; +} + +void Otto::SetRestState(bool state) { + is_otto_resting_ = state; +} + +/////////////////////////////////////////////////////////////////// +//-- PREDETERMINED MOTION SEQUENCES -----------------------------// +/////////////////////////////////////////////////////////////////// + +//--------------------------------------------------------- +//-- 统一手部动作函数 +//-- Parameters: +//-- action: 动作类型 1=举左手, 2=举右手, 3=举双手, 4=放左手, 5=放右手, 6=放双手, +//-- 7=挥左手, 8=挥右手, 9=挥双手, 10=拍打左手, 11=拍打右手, 12=拍打双手 +//-- times: 重复次数 +//-- amount: 动作幅度 (10-50) +//-- period: 动作时间 +//--------------------------------------------------------- +void Otto::HandAction(int action, int times, int amount, int period) { + // 限制参数范围 + times = 2 * std::max(3, std::min(100, times)); + amount = std::max(10, std::min(50, amount)); + period = std::max(100, std::min(1000, period)); + + int current_positions[SERVO_COUNT]; + for (int i = 0; i < SERVO_COUNT; i++) { + current_positions[i] = (servo_pins_[i] != -1) ? servo_[i].GetPosition() : servo_initial_[i]; + } + + switch (action) { + case 1: // 举左手 + current_positions[LEFT_PITCH] = 180; + MoveServos(period, current_positions); + break; + + case 2: // 举右手 + current_positions[RIGHT_PITCH] = 0; + MoveServos(period, current_positions); + break; + + case 3: // 举双手 + current_positions[LEFT_PITCH] = 180; + current_positions[RIGHT_PITCH] = 0; + MoveServos(period, current_positions); + break; + + case 4: // 放左手 + case 5: // 放右手 + case 6: // 放双手 + // 回到初始位置 + memcpy(current_positions, servo_initial_, sizeof(current_positions)); + MoveServos(period, current_positions); + break; + + case 7: // 挥左手 + current_positions[LEFT_PITCH] = 150; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[LEFT_PITCH] = 150 + (i % 2 == 0 ? -30 : 30); + MoveServos(period / 10, current_positions); + vTaskDelay(pdMS_TO_TICKS(period / 10)); + } + memcpy(current_positions, servo_initial_, sizeof(current_positions)); + MoveServos(period, current_positions); + break; + + case 8: // 挥右手 + current_positions[RIGHT_PITCH] = 30; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[RIGHT_PITCH] = 30 + (i % 2 == 0 ? 30 : -30); + MoveServos(period / 10, current_positions); + vTaskDelay(pdMS_TO_TICKS(period / 10)); + } + memcpy(current_positions, servo_initial_, sizeof(current_positions)); + MoveServos(period, current_positions); + break; + + case 9: // 挥双手 + current_positions[LEFT_PITCH] = 150; + current_positions[RIGHT_PITCH] = 30; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[LEFT_PITCH] = 150 + (i % 2 == 0 ? -30 : 30); + current_positions[RIGHT_PITCH] = 30 + (i % 2 == 0 ? 30 : -30); + MoveServos(period / 10, current_positions); + vTaskDelay(pdMS_TO_TICKS(period / 10)); + } + memcpy(current_positions, servo_initial_, sizeof(current_positions)); + MoveServos(period, current_positions); + break; + + case 10: // 拍打左手 + current_positions[LEFT_ROLL] = 20; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[LEFT_ROLL] = 20 - amount; + MoveServos(period / 10, current_positions); + current_positions[LEFT_ROLL] = 20 + amount; + MoveServos(period / 10, current_positions); + } + current_positions[LEFT_ROLL] = 0; + MoveServos(period, current_positions); + break; + + case 11: // 拍打右手 + current_positions[RIGHT_ROLL] = 160; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[RIGHT_ROLL] = 160 + amount; + MoveServos(period / 10, current_positions); + current_positions[RIGHT_ROLL] = 160 - amount; + MoveServos(period / 10, current_positions); + } + current_positions[RIGHT_ROLL] = 180; + MoveServos(period, current_positions); + break; + + case 12: // 拍打双手 + current_positions[LEFT_ROLL] = 20; + current_positions[RIGHT_ROLL] = 160; + MoveServos(period, current_positions); + for (int i = 0; i < times; i++) { + current_positions[LEFT_ROLL] = 20 - amount; + current_positions[RIGHT_ROLL] = 160 + amount; + MoveServos(period / 10, current_positions); + current_positions[LEFT_ROLL] = 20 + amount; + current_positions[RIGHT_ROLL] = 160 - amount; + MoveServos(period / 10, current_positions); + } + current_positions[LEFT_ROLL] = 0; + current_positions[RIGHT_ROLL] = 180; + MoveServos(period, current_positions); + break; + } +} + +//--------------------------------------------------------- +//-- 统一身体动作函数 +//-- Parameters: +//-- action: 动作类型 1=左转, 2=右转,3=回中心 +//-- times: 转动次数 +//-- amount: 旋转角度 (0-90度,以90度为中心左右旋转) +//-- period: 动作时间 +//--------------------------------------------------------- +void Otto::BodyAction(int action, int times, int amount, int period) { + // 限制参数范围 + times = std::max(1, std::min(10, times)); + amount = std::max(0, std::min(90, amount)); + period = std::max(500, std::min(3000, period)); + + int current_positions[SERVO_COUNT]; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + current_positions[i] = servo_[i].GetPosition(); + } else { + current_positions[i] = servo_initial_[i]; + } + } + + int body_center = servo_initial_[BODY]; + int target_angle = body_center; + + switch (action) { + case 1: // 左转 + target_angle = body_center + amount; + target_angle = std::min(180, target_angle); + break; + case 2: // 右转 + target_angle = body_center - amount; + target_angle = std::max(0, target_angle); + break; + case 3: // 回中心 + target_angle = body_center; + break; + default: + return; // 无效动作 + } + + current_positions[BODY] = target_angle; + MoveServos(period, current_positions); + vTaskDelay(pdMS_TO_TICKS(100)); +} + +//--------------------------------------------------------- +//-- 统一头部动作函数 +//-- Parameters: +//-- action: 动作类型 1=抬头, 2=低头, 3=点头, 4=回中心, 5=连续点头 +//-- times: 重复次数 (仅对连续点头有效) +//-- amount: 角度偏移 (1-15度范围内) +//-- period: 动作时间 +//--------------------------------------------------------- +void Otto::HeadAction(int action, int times, int amount, int period) { + // 限制参数范围 + times = std::max(1, std::min(10, times)); + amount = std::max(1, std::min(15, abs(amount))); + period = std::max(300, std::min(3000, period)); + + int current_positions[SERVO_COUNT]; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + current_positions[i] = servo_[i].GetPosition(); + } else { + current_positions[i] = servo_initial_[i]; + } + } + + int head_center = 90; // 头部中心位置 + + switch (action) { + case 1: // 抬头 + current_positions[HEAD] = head_center + amount; // 抬头是增加角度 + MoveServos(period, current_positions); + break; + + case 2: // 低头 + current_positions[HEAD] = head_center - amount; // 低头是减少角度 + MoveServos(period, current_positions); + break; + + case 3: // 点头 (上下运动) + // 先抬头 + current_positions[HEAD] = head_center + amount; + MoveServos(period / 3, current_positions); + vTaskDelay(pdMS_TO_TICKS(period / 6)); + + // 再低头 + current_positions[HEAD] = head_center - amount; + MoveServos(period / 3, current_positions); + vTaskDelay(pdMS_TO_TICKS(period / 6)); + + // 回到中心 + current_positions[HEAD] = head_center; + MoveServos(period / 3, current_positions); + break; + + case 4: // 回到中心位置 + current_positions[HEAD] = head_center; + MoveServos(period, current_positions); + break; + + case 5: // 连续点头 + for (int i = 0; i < times; i++) { + // 抬头 + current_positions[HEAD] = head_center + amount; + MoveServos(period / 2, current_positions); + + // 低头 + current_positions[HEAD] = head_center - amount; + MoveServos(period / 2, current_positions); + + vTaskDelay(pdMS_TO_TICKS(50)); // 短暂停顿 + } + + // 回到中心 + current_positions[HEAD] = head_center; + MoveServos(period / 2, current_positions); + break; + + default: + // 无效动作,回到中心 + current_positions[HEAD] = head_center; + MoveServos(period, current_positions); + break; + } +} diff --git a/main/boards/electron-bot/movements.h b/main/boards/electron-bot/movements.h new file mode 100644 index 0000000..bffc3ff --- /dev/null +++ b/main/boards/electron-bot/movements.h @@ -0,0 +1,89 @@ +#ifndef __MOVEMENTS_H__ +#define __MOVEMENTS_H__ + +#include "driver/gpio.h" +#include "esp_log.h" +#include "esp_timer.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "oscillator.h" + +//-- Constants +#define FORWARD 1 +#define BACKWARD -1 +#define LEFT 1 +#define RIGHT -1 +#define BOTH 0 +#define SMALL 5 +#define MEDIUM 15 +#define BIG 30 + +// -- Servo delta limit default. degree / sec +#define SERVO_LIMIT_DEFAULT 240 + +// -- Servo indexes for easy access +#define RIGHT_PITCH 0 +#define RIGHT_ROLL 1 +#define LEFT_PITCH 2 +#define LEFT_ROLL 3 +#define BODY 4 +#define HEAD 5 +#define SERVO_COUNT 6 + +class Otto { +public: + Otto(); + ~Otto(); + + //-- Otto initialization + void Init(int right_pitch, int right_roll, int left_pitch, int left_roll, int body, int head); + //-- Attach & detach functions + void AttachServos(); + void DetachServos(); + + //-- Oscillator Trims + void SetTrims(int right_pitch, int right_roll, int left_pitch, int left_roll, int body, + int head); + + //-- Predetermined Motion Functions + void MoveServos(int time, int servo_target[]); + void MoveSingle(int position, int servo_number); + void OscillateServos(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float cycle); + + //-- HOME = Otto at rest position + void Home(bool hands_down = true); + bool GetRestState(); + void SetRestState(bool state); + + // -- 手部动作 + void HandAction(int action, int times = 1, int amount = 30, int period = 1000); + // action: 1=举左手, 2=举右手, 3=举双手, 4=放左手, 5=放右手, 6=放双手, 7=挥左手, 8=挥右手, + // 9=挥双手, 10=拍打左手, 11=拍打右手, 12=拍打双手 + + //-- 身体动作 + void BodyAction(int action, int times = 1, int amount = 30, int period = 1000); + // action: 1=左转, 2=右转 + + //-- 头部动作 + void HeadAction(int action, int times = 1, int amount = 10, int period = 500); + // action: 1=抬头, 2=低头, 3=点头, 4=回中心, 5=连续点头 + +private: + Oscillator servo_[SERVO_COUNT]; + + int servo_pins_[SERVO_COUNT]; + int servo_trim_[SERVO_COUNT]; + int servo_initial_[SERVO_COUNT] = {180, 180, 0, 0, 90, 90}; + + unsigned long final_time_; + unsigned long partial_time_; + float increment_[SERVO_COUNT]; + + bool is_otto_resting_; + + void Execute(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps); +}; + +#endif // __MOVEMENTS_H__ \ No newline at end of file diff --git a/main/boards/electron-bot/oscillator.cc b/main/boards/electron-bot/oscillator.cc new file mode 100644 index 0000000..0cfc652 --- /dev/null +++ b/main/boards/electron-bot/oscillator.cc @@ -0,0 +1,149 @@ +#include "oscillator.h" + +#include +#include + +#include +#include + +extern unsigned long IRAM_ATTR millis(); + +Oscillator::Oscillator(int trim) { + trim_ = trim; + diff_limit_ = 0; + is_attached_ = false; + + sampling_period_ = 30; + period_ = 2000; + number_samples_ = period_ / sampling_period_; + inc_ = 2 * M_PI / number_samples_; + + amplitude_ = 45; + phase_ = 0; + phase0_ = 0; + offset_ = 0; + stop_ = false; + rev_ = false; + + pos_ = 90; + previous_millis_ = 0; +} + +Oscillator::~Oscillator() { + Detach(); +} + +uint32_t Oscillator::AngleToCompare(int angle) { + return (angle - SERVO_MIN_DEGREE) * (SERVO_MAX_PULSEWIDTH_US - SERVO_MIN_PULSEWIDTH_US) / + (SERVO_MAX_DEGREE - SERVO_MIN_DEGREE) + + SERVO_MIN_PULSEWIDTH_US; +} + +bool Oscillator::NextSample() { + current_millis_ = millis(); + + if (current_millis_ - previous_millis_ > sampling_period_) { + previous_millis_ = current_millis_; + return true; + } + + return false; +} + +void Oscillator::Attach(int pin, bool rev) { + if (is_attached_) { + Detach(); + } + + pin_ = pin; + rev_ = rev; + + ledc_timer_config_t ledc_timer = {.speed_mode = LEDC_LOW_SPEED_MODE, + .duty_resolution = LEDC_TIMER_13_BIT, + .timer_num = LEDC_TIMER_1, + .freq_hz = 50, + .clk_cfg = LEDC_AUTO_CLK}; + ESP_ERROR_CHECK(ledc_timer_config(&ledc_timer)); + + static int last_channel = 0; + last_channel = (last_channel + 1) % 7 + 1; + ledc_channel_ = (ledc_channel_t)last_channel; + + ledc_channel_config_t ledc_channel = {.gpio_num = pin_, + .speed_mode = LEDC_LOW_SPEED_MODE, + .channel = ledc_channel_, + .intr_type = LEDC_INTR_DISABLE, + .timer_sel = LEDC_TIMER_1, + .duty = 0, + .hpoint = 0}; + ESP_ERROR_CHECK(ledc_channel_config(&ledc_channel)); + + ledc_speed_mode_ = LEDC_LOW_SPEED_MODE; + + // pos_ = 90; + // Write(pos_); + previous_servo_command_millis_ = millis(); + + is_attached_ = true; +} + +void Oscillator::Detach() { + if (!is_attached_) + return; + + ESP_ERROR_CHECK(ledc_stop(ledc_speed_mode_, ledc_channel_, 0)); + + is_attached_ = false; +} + +void Oscillator::SetT(unsigned int T) { + period_ = T; + + number_samples_ = period_ / sampling_period_; + inc_ = 2 * M_PI / number_samples_; +} + +void Oscillator::SetPosition(int position) { + Write(position); +} + +void Oscillator::Refresh() { + if (NextSample()) { + if (!stop_) { + int pos = std::round(amplitude_ * std::sin(phase_ + phase0_) + offset_); + if (rev_) + pos = -pos; + Write(pos + 90); + } + + phase_ = phase_ + inc_; + } +} + +void Oscillator::Write(int position) { + if (!is_attached_) + return; + + long currentMillis = millis(); + if (diff_limit_ > 0) { + int limit = std::max( + 1, (((int)(currentMillis - previous_servo_command_millis_)) * diff_limit_) / 1000); + if (abs(position - pos_) > limit) { + pos_ += position < pos_ ? -limit : limit; + } else { + pos_ = position; + } + } else { + pos_ = position; + } + previous_servo_command_millis_ = currentMillis; + + int angle = pos_ + trim_; + + angle = std::min(std::max(angle, 0), 180); + + uint32_t duty = (uint32_t)(((angle / 180.0) * 2.0 + 0.5) * 8191 / 20.0); + + ESP_ERROR_CHECK(ledc_set_duty(ledc_speed_mode_, ledc_channel_, duty)); + ESP_ERROR_CHECK(ledc_update_duty(ledc_speed_mode_, ledc_channel_)); +} diff --git a/main/boards/electron-bot/oscillator.h b/main/boards/electron-bot/oscillator.h new file mode 100644 index 0000000..d9e79f2 --- /dev/null +++ b/main/boards/electron-bot/oscillator.h @@ -0,0 +1,83 @@ +#ifndef __OSCILLATOR_H__ +#define __OSCILLATOR_H__ + +#include "driver/ledc.h" +#include "esp_log.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#define M_PI 3.14159265358979323846 + +#ifndef DEG2RAD +#define DEG2RAD(g) ((g) * M_PI) / 180 +#endif + +#define SERVO_MIN_PULSEWIDTH_US 500 // 最小脉宽(微秒) +#define SERVO_MAX_PULSEWIDTH_US 2500 // 最大脉宽(微秒) +#define SERVO_MIN_DEGREE -90 // 最小角度 +#define SERVO_MAX_DEGREE 90 // 最大角度 +#define SERVO_TIMEBASE_RESOLUTION_HZ 1000000 // 1MHz, 1us per tick +#define SERVO_TIMEBASE_PERIOD 20000 // 20000 ticks, 20ms + +class Oscillator { +public: + Oscillator(int trim = 0); + ~Oscillator(); + void Attach(int pin, bool rev = false); + void Detach(); + + void SetA(unsigned int amplitude) { amplitude_ = amplitude; }; + void SetO(int offset) { offset_ = offset; }; + void SetPh(double Ph) { phase0_ = Ph; }; + void SetT(unsigned int period); + void SetTrim(int trim) { trim_ = trim; }; + void SetLimiter(int diff_limit) { diff_limit_ = diff_limit; }; + void DisableLimiter() { diff_limit_ = 0; }; + int GetTrim() { return trim_; }; + void SetPosition(int position); + void Stop() { stop_ = true; }; + void Play() { stop_ = false; }; + void Reset() { phase_ = 0; }; + void Refresh(); + int GetPosition() { return pos_; } + +private: + bool NextSample(); + void Write(int position); + uint32_t AngleToCompare(int angle); + +private: + bool is_attached_; + + //-- Oscillators parameters + unsigned int amplitude_; //-- Amplitude (degrees) + int offset_; //-- Offset (degrees) + unsigned int period_; //-- Period (miliseconds) + double phase0_; //-- Phase (radians) + + //-- Internal variables + int pos_; //-- Current servo pos + int pin_; //-- Pin where the servo is connected + int trim_; //-- Calibration offset + double phase_; //-- Current phase + double inc_; //-- Increment of phase + double number_samples_; //-- Number of samples + unsigned int sampling_period_; //-- sampling period (ms) + + long previous_millis_; + long current_millis_; + + //-- Oscillation mode. If true, the servo is stopped + bool stop_; + + //-- Reverse mode + bool rev_; + + int diff_limit_; + long previous_servo_command_millis_; + + ledc_channel_t ledc_channel_; + ledc_mode_t ledc_speed_mode_; +}; + +#endif // __OSCILLATOR_H__ \ No newline at end of file diff --git a/main/boards/electron-bot/otto_icon_font.c b/main/boards/electron-bot/otto_icon_font.c new file mode 100644 index 0000000..dc05cce --- /dev/null +++ b/main/boards/electron-bot/otto_icon_font.c @@ -0,0 +1,121 @@ +/******************************************************************************* + * Size: 20 px + * Bpp: 1 + * Opts: --bpp 1 --size 20 --no-compress --stride 1 --align 1 --font fontawesome-webfont.ttf --range 61744,61633,61480 --format lvgl -o OTTO_ICON_FONT.c + ******************************************************************************/ + +#ifdef __has_include +#if __has_include("lvgl.h") +#ifndef LV_LVGL_H_INCLUDE_SIMPLE +#define LV_LVGL_H_INCLUDE_SIMPLE +#endif +#endif +#endif + +#ifdef LV_LVGL_H_INCLUDE_SIMPLE +#include "lvgl.h" +#else +#include "lvgl/lvgl.h" +#endif + +#ifndef ENABLE_OTTO_ICON_FONT +#define ENABLE_OTTO_ICON_FONT 1 +#endif + +#if ENABLE_OTTO_ICON_FONT + +/*----------------- + * BITMAPS + *----------------*/ + +/*Store the image of the glyphs*/ +static LV_ATTRIBUTE_LARGE_CONST const uint8_t glyph_bitmap[] = { + /* U+F028 "" */ + 0x0, 0x6, 0x0, 0x10, 0xe0, 0x6, 0x6, 0x3, 0xc6, 0x60, 0xf8, 0x65, 0xff, 0x24, 0xff, 0xe6, 0x4f, 0xfc, 0x49, 0xff, 0x89, 0x3f, 0xf3, 0x27, 0xfe, 0x49, 0x87, 0xc3, 0x20, 0x78, 0xcc, 0x3, 0x3, 0x0, + 0x21, 0xc0, 0x0, 0x30, + + /* U+F0C1 "" */ + 0x1e, 0x0, 0xf, 0xc0, 0x7, 0x38, 0x3, 0x87, 0x0, 0xc0, 0xc0, 0x30, 0xb0, 0x7, 0x3c, 0x0, 0xef, 0x0, 0x1f, 0xfe, 0x3, 0xff, 0xc0, 0x7, 0x38, 0x3, 0xe7, 0x0, 0xd0, 0xc0, 0x30, 0x30, 0x6, 0x1c, 0x0, + 0xce, 0x0, 0x1f, 0x0, 0x3, 0x80, + + /* U+F130 "" */ + 0x7, 0x0, 0xfe, 0x7, 0xf0, 0x3f, 0x81, 0xfc, 0xf, 0xe0, 0x7f, 0x13, 0xf9, 0x9f, 0xcc, 0xfe, 0x67, 0xf3, 0xbf, 0xb4, 0x73, 0x18, 0x30, 0x7f, 0x0, 0x60, 0x2, 0x1, 0xff, 0x0}; + +/*--------------------- + * GLYPH DESCRIPTION + *--------------------*/ + +static const lv_font_fmt_txt_glyph_dsc_t glyph_dsc[] = {{.bitmap_index = 0, .adv_w = 0, .box_w = 0, .box_h = 0, .ofs_x = 0, .ofs_y = 0} /* id = 0 reserved */, + {.bitmap_index = 0, .adv_w = 297, .box_w = 19, .box_h = 16, .ofs_x = 0, .ofs_y = -1}, + {.bitmap_index = 38, .adv_w = 297, .box_w = 18, .box_h = 18, .ofs_x = 0, .ofs_y = -1}, + {.bitmap_index = 79, .adv_w = 206, .box_w = 13, .box_h = 18, .ofs_x = 0, .ofs_y = -1}}; + +/*--------------------- + * CHARACTER MAPPING + *--------------------*/ + +static const uint16_t unicode_list_0[] = {0x0, 0x99, 0x108}; + +/*Collect the unicode lists and glyph_id offsets*/ +static const lv_font_fmt_txt_cmap_t cmaps[] = { + {.range_start = 61480, .range_length = 265, .glyph_id_start = 1, .unicode_list = unicode_list_0, .glyph_id_ofs_list = NULL, .list_length = 3, .type = LV_FONT_FMT_TXT_CMAP_SPARSE_TINY}}; + +/*-------------------- + * ALL CUSTOM DATA + *--------------------*/ + +#if LVGL_VERSION_MAJOR == 8 +/*Store all the custom data of the font*/ +static lv_font_fmt_txt_glyph_cache_t cache; +#endif + +#if LVGL_VERSION_MAJOR >= 8 +static const lv_font_fmt_txt_dsc_t otto_icon_font_dsc = { +#else +static lv_font_fmt_txt_dsc_t otto_icon_font_dsc = { +#endif + .glyph_bitmap = glyph_bitmap, + .glyph_dsc = glyph_dsc, + .cmaps = cmaps, + .kern_dsc = NULL, + .kern_scale = 0, + .cmap_num = 1, + .bpp = 1, + .kern_classes = 0, + .bitmap_format = 0, +#if LVGL_VERSION_MAJOR == 8 + .cache = &cache +#endif + +}; + +/*----------------- + * PUBLIC FONT + *----------------*/ + +/*Initialize a public general font descriptor*/ +#if LVGL_VERSION_MAJOR >= 8 +const lv_font_t OTTO_ICON_FONT = { +#else +lv_font_t OTTO_ICON_FONT = { +#endif + .get_glyph_dsc = lv_font_get_glyph_dsc_fmt_txt, /*Function pointer to get glyph's data*/ + .get_glyph_bitmap = lv_font_get_bitmap_fmt_txt, /*Function pointer to get glyph's bitmap*/ + .line_height = 18, /*The maximum line height required by the font*/ + .base_line = 1, /*Baseline measured from the bottom of the line*/ +#if !(LVGL_VERSION_MAJOR == 6 && LVGL_VERSION_MINOR == 0) + .subpx = LV_FONT_SUBPX_NONE, +#endif +#if LV_VERSION_CHECK(7, 4, 0) || LVGL_VERSION_MAJOR >= 8 + .underline_position = 0, + .underline_thickness = 0, +#endif + .static_bitmap = 0, + .dsc = &otto_icon_font_dsc, /*The custom font data. Will be accessed by `get_glyph_bitmap/dsc` */ +#if LV_VERSION_CHECK(8, 2, 0) || LVGL_VERSION_MAJOR >= 9 + .fallback = NULL, +#endif + .user_data = NULL, +}; + +#endif /*#if ENABLE_OTTO_ICON_FONT*/ diff --git a/main/boards/electron-bot/power_manager.h b/main/boards/electron-bot/power_manager.h new file mode 100644 index 0000000..13d8ff3 --- /dev/null +++ b/main/boards/electron-bot/power_manager.h @@ -0,0 +1,128 @@ +#ifndef __POWER_MANAGER_H__ +#define __POWER_MANAGER_H__ + +#include +#include +#include +#include + +class PowerManager { +private: + // 电池电量区间-分压电阻为2个100k + static constexpr struct { + uint16_t adc; + uint8_t level; + } BATTERY_LEVELS[] = {{2150, 0}, {2450, 100}}; + static constexpr size_t BATTERY_LEVELS_COUNT = 2; + static constexpr size_t ADC_VALUES_COUNT = 10; + + esp_timer_handle_t timer_handle_ = nullptr; + gpio_num_t charging_pin_; + adc_unit_t adc_unit_; + adc_channel_t adc_channel_; + uint16_t adc_values_[ADC_VALUES_COUNT]; + size_t adc_values_index_ = 0; + size_t adc_values_count_ = 0; + uint8_t battery_level_ = 100; + bool is_charging_ = false; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + is_charging_ = gpio_get_level(charging_pin_) == 0; + ReadBatteryAdcData(); + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, adc_channel_, &adc_value)); + + adc_values_[adc_values_index_] = adc_value; + adc_values_index_ = (adc_values_index_ + 1) % ADC_VALUES_COUNT; + if (adc_values_count_ < ADC_VALUES_COUNT) { + adc_values_count_++; + } + + uint32_t average_adc = 0; + for (size_t i = 0; i < adc_values_count_; i++) { + average_adc += adc_values_[i]; + } + average_adc /= adc_values_count_; + + CalculateBatteryLevel(average_adc); + + // ESP_LOGI("PowerManager", "ADC值: %d 平均值: %ld 电量: %u%%", adc_value, average_adc, + // battery_level_); + } + + void CalculateBatteryLevel(uint32_t average_adc) { + if (average_adc <= BATTERY_LEVELS[0].adc) { + battery_level_ = 0; + } else if (average_adc >= BATTERY_LEVELS[BATTERY_LEVELS_COUNT - 1].adc) { + battery_level_ = 100; + } else { + float ratio = static_cast(average_adc - BATTERY_LEVELS[0].adc) / + (BATTERY_LEVELS[1].adc - BATTERY_LEVELS[0].adc); + battery_level_ = ratio * 100; + } + } + +public: + PowerManager(gpio_num_t charging_pin, adc_unit_t adc_unit = ADC_UNIT_2, + adc_channel_t adc_channel = ADC_CHANNEL_3) + : charging_pin_(charging_pin), adc_unit_(adc_unit), adc_channel_(adc_channel) { + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + esp_timer_create_args_t timer_args = { + .callback = + [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); // 1秒 + + InitializeAdc(); + } + + void InitializeAdc() { + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = adc_unit_, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, adc_channel_, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { return is_charging_; } + + uint8_t GetBatteryLevel() { return battery_level_; } +}; +#endif // __POWER_MANAGER_H__ \ No newline at end of file diff --git a/main/boards/esp-box-3/README.md b/main/boards/esp-box-3/README.md new file mode 100644 index 0000000..103f732 --- /dev/null +++ b/main/boards/esp-box-3/README.md @@ -0,0 +1,132 @@ +# ESP-BOX-3 + +## 简介 + + + +ESP-BOX-3 是乐鑫官方开发的 AIoT 开发套件,搭载 ESP32-S3-WROOM-1 模组,配备 2.4 英寸 320x240 ILI9341 显示屏,双麦克风阵列,支持离线语音唤醒与设备端回声消除(AEC)功能。 + +## 硬件特性 + +- **主控**: ESP32-S3-WROOM-1 (16MB Flash, 8MB PSRAM) +- **显示屏**: 2.4 英寸 IPS LCD (320x240, ILI9341) +- **音频**: ES8311 音频 Codec + ES7210 双麦 ADC +- **音频功能**: 支持设备端 AEC (回声消除) +- **按键**: Boot 按键 (单击/双击功能) +- **其他**: USB-C 供电与通信 + +## 配置、编译命令 + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig 并配置** + +```bash +idf.py menuconfig +``` + +分别配置如下选项: + +### 基本配置 +- `Xiaozhi Assistant` → `Board Type` → 选择 `ESP BOX 3` + +### UI风格选择 + +ESP-BOX-3 支持多种不同的 UI 显示风格,通过 menuconfig 配置选择: + +- `Xiaozhi Assistant` → `Select display style` → 选择显示风格 + +#### 可选风格 + +##### 表情动画风格 (Emote animation style) - 推荐 +- **配置选项**: `USE_EMOTE_MESSAGE_STYLE` +- **特点**: 使用自定义的 `EmoteDisplay` 表情显示系统 +- **功能**: 支持丰富的表情动画、眼睛动画、状态图标显示 +- **适用**: 智能助手场景,提供更生动的人机交互体验 +- **类**: `emote::EmoteDisplay` + +**⚠️ 重要**: 选择此风格需要额外配置自定义资源文件: +1. `Xiaozhi Assistant` → `Flash Assets` → 选择 `Flash Custom Assets` +2. `Xiaozhi Assistant` → `Custom Assets File` → 填入资源文件地址: + ``` + https://dl.espressif.com/AE/wn9_nihaoxiaozhi_tts-font_puhui_common_20_4-esp-box-3.bin + ``` + +##### 默认消息风格 (Enable default message style) +- **配置选项**: `USE_DEFAULT_MESSAGE_STYLE` (默认) +- **特点**: 使用标准的消息显示界面 +- **功能**: 传统的文本和图标显示界面 +- **适用**: 标准的对话场景 +- **类**: `SpiLcdDisplay` + +##### 微信消息风格 (Enable WeChat Message Style) +- **配置选项**: `USE_WECHAT_MESSAGE_STYLE` +- **特点**: 仿微信聊天界面风格 +- **功能**: 类似微信的消息气泡显示 +- **适用**: 喜欢微信风格的用户 +- **类**: `SpiLcdDisplay` + +### 音频功能配置 + +#### 设备端回声消除 (AEC) +- `Xiaozhi Assistant` → `Enable Device-Side AEC` → 启用 + +ESP-BOX-3 硬件支持设备端 AEC 功能,可有效消除扬声器播放声音对麦克风的干扰,提升语音识别准确率。 + +**运行时切换**: 双击 Boot 按键可在运行时开启/关闭 AEC 功能。 + +> **说明**: 设备端 AEC 需要干净的扬声器输出参考路径和良好的麦克风与扬声器物理隔离才能正常工作。ESP-BOX-3 硬件已做优化设计。 + +### 唤醒词配置 + +ESP-BOX-3 支持多种唤醒词实现方式: + +- `Xiaozhi Assistant` → `Wake Word Implementation Type` → 选择唤醒词类型 + +推荐选择: +- **Wakenet model with AFE** (`USE_AFE_WAKE_WORD`) - 支持 AEC 的唤醒词检测 + +按 `S` 保存,按 `Q` 退出。 + +**编译** + +```bash +idf.py build +``` + +**烧录** + +将 ESP-BOX-3 连接至电脑,并运行: + +```bash +idf.py flash +``` + +## 按键说明 + +### Boot 按键功能 + +#### 单击 +- **配网状态**: 进入 WiFi 配置模式 +- **空闲状态**: 开始对话 +- **对话中**: 打断或停止当前对话 + +#### 双击 (需启用设备端 AEC) +- **空闲状态**: 切换 AEC 开启/关闭 + +## 常见问题 + +### 1. 为什么需要设备端 AEC? +设备端 AEC 可以在本地实时消除扬声器播放声音对麦克风的干扰,在播放音乐或 TTS 回复时仍能准确识别语音指令。 + +### 2. 表情动画风格无法显示? +请确保已经配置了正确的自定义资源文件地址,并且设备能够访问该 URL 下载资源。 + +### 3. 如何恢复出厂设置? +长按 Boot 按键 3 秒以上,设备会清除所有配置并重启。 diff --git a/main/boards/esp-box-3/config.h b/main/boards/esp-box-3/config.h new file mode 100644 index 0000000..f045304 --- /dev/null +++ b/main/boards/esp-box-3/config.h @@ -0,0 +1,41 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_2 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_18 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_47 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-box-3/config.json b/main/boards/esp-box-3/config.json new file mode 100644 index 0000000..518936d --- /dev/null +++ b/main/boards/esp-box-3/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-box-3", + "sdkconfig_append": [ + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_USE_EMOTE_MESSAGE_STYLE=y", + "CONFIG_FLASH_CUSTOM_ASSETS=y", + "CONFIG_CUSTOM_ASSETS_FILE=\"https://dl.espressif.com/AE/wn9_nihaoxiaozhi_tts-font_puhui_common_20_4-esp-box-3.bin\"" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp-box-3/emote.json b/main/boards/esp-box-3/emote.json new file mode 100644 index 0000000..abc11c8 --- /dev/null +++ b/main/boards/esp-box-3/emote.json @@ -0,0 +1,22 @@ +[ + {"emote": "happy", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "laughing", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "funny", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "loving", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "embarrassed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confident", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "delicious", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "sad", "src": "Sad.eaf", "loop": true, "fps": 20}, + {"emote": "crying", "src": "cry.eaf", "loop": true, "fps": 20}, + {"emote": "sleepy", "src": "sleep.eaf", "loop": true, "fps": 20}, + {"emote": "silly", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "angry", "src": "angry.eaf", "loop": true, "fps": 20}, + {"emote": "surprised", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "shocked", "src": "shocked.eaf", "loop": true, "fps": 20}, + {"emote": "thinking", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "winking", "src": "neutral.eaf", "loop": true, "fps": 20}, + {"emote": "relaxed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confused", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "neutral", "src": "winking.eaf", "loop": false, "fps": 20}, + {"emote": "idle", "src": "neutral.eaf", "loop": false, "fps": 20} +] diff --git a/main/boards/esp-box-3/esp_box3_board.cc b/main/boards/esp-box-3/esp_box3_board.cc new file mode 100644 index 0000000..7e1c600 --- /dev/null +++ b/main/boards/esp-box-3/esp_box3_board.cc @@ -0,0 +1,175 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/display.h" +#include "display/emote_display.h" +#include "display/lcd_display.h" +#include "esp_lcd_ili9341.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include +#include +#include +#include + +#define TAG "EspBox3Board" + +// Init ili9341 by custom cmd +static const ili9341_lcd_init_cmd_t vendor_specific_init[] = { + {0xC8, (uint8_t []){0xFF, 0x93, 0x42}, 3, 0}, + {0xC0, (uint8_t []){0x0E, 0x0E}, 2, 0}, + {0xC5, (uint8_t []){0xD0}, 1, 0}, + {0xC1, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0x00, 0x03, 0x08, 0x06, 0x13, 0x09, 0x39, 0x39, 0x48, 0x02, 0x0a, 0x08, 0x17, 0x17, 0x0F}, 15, 0}, + {0xE1, (uint8_t []){0x00, 0x28, 0x29, 0x01, 0x0d, 0x03, 0x3f, 0x33, 0x52, 0x04, 0x0f, 0x0e, 0x37, 0x38, 0x0F}, 15, 0}, + + {0xB1, (uint8_t []){00, 0x1B}, 2, 0}, + {0x36, (uint8_t []){0x08}, 1, 0}, + {0x3A, (uint8_t []){0x55}, 1, 0}, + {0xB7, (uint8_t []){0x06}, 1, 0}, + + {0x11, (uint8_t []){0}, 0x80, 0}, + {0x29, (uint8_t []){0}, 0x80, 0}, + + {0, (uint8_t []){0}, 0xff, 0}, +}; + +class EspBox3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Display* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_6; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_7; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeIli9341Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_5; + io_config.dc_gpio_num = GPIO_NUM_4; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const ili9341_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(ili9341_lcd_init_cmd_t), + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_48; + panel_config.flags.reset_active_high = 1, + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *)&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + +#if CONFIG_USE_EMOTE_MESSAGE_STYLE + display_ = new emote::EmoteDisplay(panel, panel_io, DISPLAY_WIDTH, DISPLAY_HEIGHT); +#else + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); +#endif + } + +public: + EspBox3Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeIli9341Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(EspBox3Board); diff --git a/main/boards/esp-box-3/layout.json b/main/boards/esp-box-3/layout.json new file mode 100644 index 0000000..8a1dfbc --- /dev/null +++ b/main/boards/esp-box-3/layout.json @@ -0,0 +1,37 @@ +[ + { + "name": "eye_anim", + "align": "GFX_ALIGN_LEFT_MID", + "x": 10, + "y": 30 + }, + { + "name": "status_icon", + "align": "GFX_ALIGN_TOP_MID", + "x": -120, + "y": 18 + }, + { + "name": "toast_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 20, + "width": 200, + "height": 40 + }, + { + "name": "clock_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 20, + "width": 200, + "height": 50 + }, + { + "name": "listen_anim", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 5 + } +] + \ No newline at end of file diff --git a/main/boards/esp-box-lite/box_audio_codec_lite.cc b/main/boards/esp-box-lite/box_audio_codec_lite.cc new file mode 100644 index 0000000..658f49a --- /dev/null +++ b/main/boards/esp-box-lite/box_audio_codec_lite.cc @@ -0,0 +1,272 @@ +#include "box_audio_codec_lite.h" + +#include +#include +#include +#include + +static const char TAG[] = "BoxAudioCodecLite"; + +BoxAudioCodecLite::BoxAudioCodecLite(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + if (input_reference) { + ref_buffer_.resize(960 * 2); + } + input_channels_ = 2 + input_reference_; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = (i2c_port_t)1, + .addr = ES8156_CODEC_DEFAULT_ADDR, + .bus_handle = i2c_master_handle, + }; + out_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(out_ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8156_codec_cfg_t cfg = {}; + cfg.ctrl_if = out_ctrl_if_; + cfg.gpio_if = gpio_if_; + cfg.pa_pin = pa_pin; + cfg.hw_gain.pa_voltage = 5.0; + cfg.hw_gain.codec_dac_voltage = 3.3; + out_codec_if_ = es8156_codec_new(&cfg); + assert(out_codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = out_codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + + // Input + i2c_cfg.addr = ES7243E_CODEC_DEFAULT_ADDR; + in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7243e_codec_cfg_t es7243_cfg = {}; + es7243_cfg.ctrl_if = in_ctrl_if_; + in_codec_if_ = es7243e_codec_new(&es7243_cfg); + assert(in_codec_if_ != NULL); + + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + dev_cfg.codec_if = in_codec_if_; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + + ESP_LOGI(TAG, "BoxAudioDevice initialized"); +} + +BoxAudioCodecLite::~BoxAudioCodecLite() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void BoxAudioCodecLite::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = I2S_STD_PHILIP_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO), + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + i2s_tdm_config_t tdm_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + .bclk_div = 8, + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = i2s_tdm_slot_mask_t(I2S_TDM_SLOT0 | I2S_TDM_SLOT1 | I2S_TDM_SLOT2 | I2S_TDM_SLOT3), + .ws_width = I2S_TDM_AUTO_WS_WIDTH, + .ws_pol = false, + .bit_shift = true, + .left_align = false, + .big_endian = false, + .bit_order_lsb = false, + .skip_mask = false, + .total_slot = I2S_TDM_AUTO_SLOT_NUM + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = I2S_GPIO_UNUSED, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_tdm_mode(rx_handle_, &tdm_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void BoxAudioCodecLite::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void BoxAudioCodecLite::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = (uint8_t)(input_channels_ - input_reference_), + .channel_mask = 0, + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + for (int i = 0;i < fs.channel; i++) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(i); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + // 麦克风增益解决收音太小的问题 + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, 37.5)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void BoxAudioCodecLite::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + } + AudioCodec::EnableOutput(enable); +} + +int BoxAudioCodecLite::Read(int16_t* dest, int samples) { + if (input_enabled_) { + if (!input_reference_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + else { + int size = samples / input_channels_; + int channels = input_channels_ - input_reference_; + std::vector data(size * channels); + // read mic data + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)data.data(), data.size() * sizeof(int16_t))); + int j = 0; + int i = 0; + while (i< samples) { + // mic data + for (int p = 0; p < channels; p++) { + dest[i++] = data[j++]; + } + // ref data + dest[i++] = read_pos_ < write_pos_? ref_buffer_[read_pos_++] : 0; + } + + if (read_pos_ == write_pos_) { + read_pos_ = write_pos_ = 0; + } + } + } + return samples; +} + +int BoxAudioCodecLite::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + if (input_reference_) { // 板子不支持硬件回采,采用缓存播放缓冲来实现回声消除 + if (write_pos_ - read_pos_ + samples > ref_buffer_.size()) { + assert(ref_buffer_.size() >= samples); + // 写溢出,只保留最近的数据 + read_pos_ = write_pos_ + samples - ref_buffer_.size(); + } + if (read_pos_) { + if (write_pos_ != read_pos_) { + memmove(ref_buffer_.data(), ref_buffer_.data() + read_pos_, (write_pos_ - read_pos_) * sizeof(int16_t)); + } + write_pos_ -= read_pos_; + read_pos_ = 0; + } + memcpy(&ref_buffer_[write_pos_], data, samples * sizeof(int16_t)); + write_pos_ += samples; + } + } + return samples; +} \ No newline at end of file diff --git a/main/boards/esp-box-lite/box_audio_codec_lite.h b/main/boards/esp-box-lite/box_audio_codec_lite.h new file mode 100644 index 0000000..50fd361 --- /dev/null +++ b/main/boards/esp-box-lite/box_audio_codec_lite.h @@ -0,0 +1,41 @@ +#ifndef _BOX_AUDIO_CODEC_LITE_H +#define _BOX_AUDIO_CODEC_LITE_H + +#include "audio_codec.h" + +#include +#include + +class BoxAudioCodecLite : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + // ref buffer used for aec + std::vector ref_buffer_; + int read_pos_ = 0; + int write_pos_ = 0; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + BoxAudioCodecLite(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, bool input_reference); + virtual ~BoxAudioCodecLite(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_LITE_H diff --git a/main/boards/esp-box-lite/config.h b/main/boards/esp-box-lite/config.h new file mode 100644 index 0000000..ee345ed --- /dev/null +++ b/main/boards/esp-box-lite/config.h @@ -0,0 +1,39 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_INPUT_REFERENCE CONFIG_USE_AUDIO_PROCESSOR + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_2 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_47 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_18 + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_45 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-box-lite/config.json b/main/boards/esp-box-lite/config.json new file mode 100644 index 0000000..870fabe --- /dev/null +++ b/main/boards/esp-box-lite/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-box-lite", + "sdkconfig_append": [ + "CONFIG_SOC_ADC_SUPPORTED=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp-box-lite/esp_box_lite_board.cc b/main/boards/esp-box-lite/esp_box_lite_board.cc new file mode 100644 index 0000000..ca7dd6a --- /dev/null +++ b/main/boards/esp-box-lite/esp_box_lite_board.cc @@ -0,0 +1,237 @@ +#include "wifi_board.h" +#include "box_audio_codec_lite.h" +#include "display/lcd_display.h" +#include "esp_lcd_ili9341.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "EspBoxBoardLite" + +/* ADC Buttons */ +typedef enum { + BSP_ADC_BUTTON_PREV, + BSP_ADC_BUTTON_ENTER, + BSP_ADC_BUTTON_NEXT, + BSP_ADC_BUTTON_NUM +} bsp_adc_button_t; + +// Init ili9341 by custom cmd +static const ili9341_lcd_init_cmd_t vendor_specific_init[] = { + {0xC8, (uint8_t []){0xFF, 0x93, 0x42}, 3, 0}, + {0xC0, (uint8_t []){0x0E, 0x0E}, 2, 0}, + {0xC5, (uint8_t []){0xD0}, 1, 0}, + {0xC1, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0x00, 0x03, 0x08, 0x06, 0x13, 0x09, 0x39, 0x39, 0x48, 0x02, 0x0a, 0x08, 0x17, 0x17, 0x0F}, 15, 0}, + {0xE1, (uint8_t []){0x00, 0x28, 0x29, 0x01, 0x0d, 0x03, 0x3f, 0x33, 0x52, 0x04, 0x0f, 0x0e, 0x37, 0x38, 0x0F}, 15, 0}, + + {0xB1, (uint8_t []){00, 0x1B}, 2, 0}, + {0x36, (uint8_t []){0x08}, 1, 0}, + {0x3A, (uint8_t []){0x55}, 1, 0}, + {0xB7, (uint8_t []){0x06}, 1, 0}, + + {0x11, (uint8_t []){0}, 0x80, 0}, + {0x29, (uint8_t []){0}, 0x80, 0}, + + {0, (uint8_t []){0}, 0xff, 0}, +}; + +class EspBoxBoardLite : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button* adc_button_[BSP_ADC_BUTTON_NUM]; +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) + adc_oneshot_unit_handle_t bsp_adc_handle = NULL; +#endif + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_6; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_7; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void ChangeVol(int val) { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + val; + if (volume > 100) { + volume = 100; + } + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + } + + void TogleState() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + + void InitializeButtons() { + /* Initialize ADC esp-box lite的前三个按钮采用是的adc按钮,而非gpio */ + button_adc_config_t adc_cfg = {}; + adc_cfg.adc_channel = ADC_CHANNEL_0; // ADC1 channel 0 is GPIO1 +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) + const adc_oneshot_unit_init_cfg_t init_config1 = { + .unit_id = ADC_UNIT_1, + }; + adc_oneshot_new_unit(&init_config1, &bsp_adc_handle); + adc_cfg.adc_handle = &bsp_adc_handle; +#endif + adc_cfg.button_index = BSP_ADC_BUTTON_PREV; + adc_cfg.min = 2310; // middle is 2410mV + adc_cfg.max = 2510; + adc_button_[0] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_ENTER; + adc_cfg.min = 1880; // middle is 1980mV + adc_cfg.max = 2080; + adc_button_[1] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_NEXT; + adc_cfg.min = 720; // middle is 820mV + adc_cfg.max = 920; + + adc_button_[2] = new AdcButton(adc_cfg); + + auto volume_up_button = adc_button_[BSP_ADC_BUTTON_NEXT]; + volume_up_button->OnClick([this]() {ChangeVol(10);}); + volume_up_button->OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + auto volume_down_button = adc_button_[BSP_ADC_BUTTON_PREV]; + volume_down_button->OnClick([this]() {ChangeVol(-10);}); + volume_down_button->OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + auto break_button = adc_button_[BSP_ADC_BUTTON_ENTER]; + break_button->OnClick([this]() {TogleState();}); + boot_button_.OnClick([this]() {TogleState();}); + } + + void InitializeIli9341Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_5; + io_config.dc_gpio_num = GPIO_NUM_4; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const ili9341_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(ili9341_lcd_init_cmd_t), + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_48; + panel_config.flags.reset_active_high = 0, + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *)&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + EspBoxBoardLite() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeIli9341Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + ~EspBoxBoardLite() { + for (int i =0; i + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_2 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_47 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_18 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_45 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-box/config.json b/main/boards/esp-box/config.json new file mode 100644 index 0000000..0ae7e20 --- /dev/null +++ b/main/boards/esp-box/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-box", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp-box/esp_box_board.cc b/main/boards/esp-box/esp_box_board.cc new file mode 100644 index 0000000..4dcbca8 --- /dev/null +++ b/main/boards/esp-box/esp_box_board.cc @@ -0,0 +1,168 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "esp_lcd_ili9341.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include +#include +#include +#include + +#define TAG "EspBoxBoard" + +// Init ili9341 by custom cmd +static const ili9341_lcd_init_cmd_t vendor_specific_init[] = { + {0xC8, (uint8_t []){0xFF, 0x93, 0x42}, 3, 0}, + {0xC0, (uint8_t []){0x0E, 0x0E}, 2, 0}, + {0xC5, (uint8_t []){0xD0}, 1, 0}, + {0xC1, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0x00, 0x03, 0x08, 0x06, 0x13, 0x09, 0x39, 0x39, 0x48, 0x02, 0x0a, 0x08, 0x17, 0x17, 0x0F}, 15, 0}, + {0xE1, (uint8_t []){0x00, 0x28, 0x29, 0x01, 0x0d, 0x03, 0x3f, 0x33, 0x52, 0x04, 0x0f, 0x0e, 0x37, 0x38, 0x0F}, 15, 0}, + + {0xB1, (uint8_t []){00, 0x1B}, 2, 0}, + {0x36, (uint8_t []){0x08}, 1, 0}, + {0x3A, (uint8_t []){0x55}, 1, 0}, + {0xB7, (uint8_t []){0x06}, 1, 0}, + + {0x11, (uint8_t []){0}, 0x80, 0}, + {0x29, (uint8_t []){0}, 0x80, 0}, + + {0, (uint8_t []){0}, 0xff, 0}, +}; + +class EspBox3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_6; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_7; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeIli9341Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_5; + io_config.dc_gpio_num = GPIO_NUM_4; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const ili9341_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(ili9341_lcd_init_cmd_t), + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_48; + panel_config.flags.reset_active_high = 0, + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *)&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + EspBox3Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeIli9341Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(EspBox3Board); diff --git a/main/boards/esp-hi/README.md b/main/boards/esp-hi/README.md new file mode 100644 index 0000000..8921f1f --- /dev/null +++ b/main/boards/esp-hi/README.md @@ -0,0 +1,51 @@ +# ESP-Hi + +## 简介 + + + +ESP-Hi 是 ESP Friends 开源的一款基于 ESP32C3 的超**低成本** AI 对话机器人。ESP-Hi 集成了一个0.96寸的彩屏,用于显示表情,**机器狗已实现数十种动作**。通过对 ESP32-C3 外设的充分挖掘,仅需最少的板级硬件即可实现拾音和发声,同步优化了软件,降低内存与 Flash 占用,在资源受限的情况下同时实现了**唤醒词检测**与多种外设驱动。硬件详情等可查看[立创开源项目](https://oshwhub.com/esp-college/esp-hi)。 + +## WebUI + +ESP-Hi x 小智内置了一个控制身体运动的 WebUI,请将手机与 ESP-Hi 连接到同一个 Wi-Fi 下,手机访问 `http://esp-hi.local/` 以使用。 + +如需禁用,请取消 `ESP_HI_WEB_CONTROL_ENABLED`,即取消勾选 `Component config` → `Servo Dog Configuration` → `Web Control` → `Enable ESP-HI Web Control`。 + +## 配置、编译命令 + +由于 ESP-Hi 需要配置较多的 sdkconfig 选项,推荐使用编译脚本编译。 + +**编译** + +```bash +python ./scripts/release.py esp-hi +``` + +如需手动编译,请参考 `esp-hi/config.json` 修改 menuconfig 对应选项。 + +**烧录** + +```bash +idf.py flash +``` + + +> [!TIP] +> +> **舵机控制会占用 ESP-Hi 的 USB Type-C 接口**,导致无法连接电脑(无法烧录/查看运行日志)。如遇此情况,请按以下提示操作: +> +> **烧录** +> +> 1. 断开 ESP-Hi 的电源,只留头部,不要连接身体。 +> 2. 按住 ESP-Hi 的按钮并连接电脑。 +> +> 此时,ESP-Hi (ESP32C3) 应当处于烧录模式,可以使用电脑烧录程序。烧录完成后,可能需要重新插拔电源。 +> +> **查看 log** +> +> 请设置 `CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y`,即 `Component config` → `ESP System Settings` → `Channel for console output` 选择 `USB Serial/JTAG Controller`。这同时会禁用舵机控制功能。 diff --git a/main/boards/esp-hi/adc_pdm_audio_codec.cc b/main/boards/esp-hi/adc_pdm_audio_codec.cc new file mode 100644 index 0000000..db5d8e1 --- /dev/null +++ b/main/boards/esp-hi/adc_pdm_audio_codec.cc @@ -0,0 +1,249 @@ +#include "adc_pdm_audio_codec.h" + +#include +#include +#include +#include +#include +#include "adc_mic.h" +#include "driver/i2s_pdm.h" +#include "soc/gpio_sig_map.h" +#include "soc/io_mux_reg.h" +#include "hal/rtc_io_hal.h" +#include "hal/gpio_ll.h" +#include "settings.h" +#include "config.h" + +static const char TAG[] = "AdcPdmAudioCodec"; + +#define BSP_I2S_GPIO_CFG(_dout) \ + { \ + .clk = GPIO_NUM_NC, \ + .dout = _dout, \ + .invert_flags = { \ + .clk_inv = false, \ + }, \ + } + +/** + * @brief Mono Duplex I2S configuration structure + * + * This configuration is used by default in bsp_audio_init() + */ +#define BSP_I2S_DUPLEX_MONO_CFG(_sample_rate, _dout) \ + { \ + .clk_cfg = I2S_PDM_TX_CLK_DEFAULT_CONFIG(_sample_rate), \ + .slot_cfg = I2S_PDM_TX_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO), \ + .gpio_cfg = BSP_I2S_GPIO_CFG(_dout), \ + } + +AdcPdmAudioCodec::AdcPdmAudioCodec(int input_sample_rate, int output_sample_rate, + uint32_t adc_mic_channel, gpio_num_t pdm_speak_p,gpio_num_t pdm_speak_n, gpio_num_t pa_ctl) { + + input_reference_ = false; + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + uint8_t adc_channel[1] = {0}; + adc_channel[0] = adc_mic_channel; + + audio_codec_adc_cfg_t cfg = { + .handle = NULL, + .max_store_buf_size = 1024 * 2, + .conv_frame_size = 1024, + .unit_id = ADC_UNIT_1, + .adc_channel_list = adc_channel, + .adc_channel_num = sizeof(adc_channel) / sizeof(adc_channel[0]), + .sample_rate_hz = (uint32_t)input_sample_rate, + }; + const audio_codec_data_if_t *adc_if = audio_codec_new_adc_data(&cfg); + + esp_codec_dev_cfg_t codec_dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_IN, + .data_if = adc_if, + }; + input_dev_ = esp_codec_dev_new(&codec_dev_cfg); + if (!input_dev_) { + ESP_LOGE(TAG, "Failed to create codec device"); + return; + } + + i2s_chan_config_t chan_cfg = I2S_CHANNEL_DEFAULT_CONFIG(I2S_NUM_0, I2S_ROLE_MASTER); + chan_cfg.auto_clear = true; // Auto clear the legacy data in the DMA buffer + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, NULL)); + + i2s_pdm_tx_config_t pdm_cfg_default = BSP_I2S_DUPLEX_MONO_CFG((uint32_t)output_sample_rate, pdm_speak_p); + pdm_cfg_default.clk_cfg.up_sample_fs = AUDIO_PDM_UPSAMPLE_FS; + pdm_cfg_default.slot_cfg.sd_scale = I2S_PDM_SIG_SCALING_MUL_4; + pdm_cfg_default.slot_cfg.hp_scale = I2S_PDM_SIG_SCALING_MUL_4; + pdm_cfg_default.slot_cfg.lp_scale = I2S_PDM_SIG_SCALING_MUL_4; + pdm_cfg_default.slot_cfg.sinc_scale = I2S_PDM_SIG_SCALING_MUL_4; + const i2s_pdm_tx_config_t *p_i2s_cfg = &pdm_cfg_default; + + ESP_ERROR_CHECK(i2s_channel_init_pdm_tx_mode(tx_handle_, p_i2s_cfg)); + + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = NULL, + .tx_handle = tx_handle_, + }; + + const audio_codec_data_if_t *i2s_data_if = audio_codec_new_i2s_data(&i2s_cfg); + + codec_dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_OUT; + codec_dev_cfg.codec_if = NULL; + codec_dev_cfg.data_if = i2s_data_if; + output_dev_ = esp_codec_dev_new(&codec_dev_cfg); + + output_volume_ = 100; + if(pa_ctl != GPIO_NUM_NC) { + pa_ctrl_pin_ = pa_ctl; + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << pa_ctrl_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + } + gpio_set_drive_capability(pdm_speak_p, GPIO_DRIVE_CAP_0); + + if(pdm_speak_n != GPIO_NUM_NC){ + PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[pdm_speak_n], PIN_FUNC_GPIO); + gpio_set_direction(pdm_speak_n, GPIO_MODE_OUTPUT); + esp_rom_gpio_connect_out_signal(pdm_speak_n, I2SO_SD_OUT_IDX, 1, 0); //反转输出 SD OUT 信号 + gpio_set_drive_capability(pdm_speak_n, GPIO_DRIVE_CAP_0); + } + + // 初始化输出定时器 + esp_timer_create_args_t output_timer_args = { + .callback = &AdcPdmAudioCodec::OutputTimerCallback, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "output_timer" + }; + ESP_ERROR_CHECK(esp_timer_create(&output_timer_args, &output_timer_)); + + ESP_LOGI(TAG, "AdcPdmAudioCodec initialized"); +} + +AdcPdmAudioCodec::~AdcPdmAudioCodec() { + // 删除定时器 + if (output_timer_) { + esp_timer_stop(output_timer_); + esp_timer_delete(output_timer_); + output_timer_ = nullptr; + } + + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); +} + +void AdcPdmAudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void AdcPdmAudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)input_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void AdcPdmAudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + + // 强制按板卡配置重配PDM TX时钟,覆盖第三方库在set_fmt中的默认up_sample_fs + // 若通道已启用,先禁用再重配,最后再启用 + ESP_ERROR_CHECK_WITHOUT_ABORT(i2s_channel_disable(tx_handle_)); + i2s_pdm_tx_clk_config_t clk_cfg = I2S_PDM_TX_CLK_DEFAULT_CONFIG((uint32_t)output_sample_rate_); + clk_cfg.up_sample_fs = AUDIO_PDM_UPSAMPLE_FS; + ESP_ERROR_CHECK(i2s_channel_reconfig_pdm_tx_clock(tx_handle_, &clk_cfg)); + ESP_ERROR_CHECK(i2s_channel_enable(tx_handle_)); + if(pa_ctrl_pin_ != GPIO_NUM_NC){ + gpio_set_level(pa_ctrl_pin_, 1); + } + // 启用输出时启动定时器 + if (output_timer_) { + esp_timer_start_once(output_timer_, TIMER_TIMEOUT_US); + } + + } else { + // 禁用输出时停止定时器 + if (output_timer_) { + esp_timer_stop(output_timer_); + } + if(pa_ctrl_pin_ != GPIO_NUM_NC){ + gpio_set_level(pa_ctrl_pin_, 0); + } + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + } + AudioCodec::EnableOutput(enable); +} + +int AdcPdmAudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} +int AdcPdmAudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + // 重置输出定时器 + if (output_timer_) { + esp_timer_stop(output_timer_); + esp_timer_start_once(output_timer_, TIMER_TIMEOUT_US); + } + } + return samples; +} + +void AdcPdmAudioCodec::Start() { + Settings settings("audio", false); + output_volume_ = settings.GetInt("output_volume", output_volume_); + if (output_volume_ <= 0) { + ESP_LOGW(TAG, "Output volume value (%d) is too small, setting to default (10)", output_volume_); + output_volume_ = 10; + } + + EnableInput(true); + EnableOutput(true); + ESP_LOGI(TAG, "Audio codec started"); +} + +// 定时器回调函数实现 +void AdcPdmAudioCodec::OutputTimerCallback(void* arg) { + AdcPdmAudioCodec* codec = static_cast(arg); + if (codec && codec->output_enabled_) { + codec->EnableOutput(false); + } +} diff --git a/main/boards/esp-hi/adc_pdm_audio_codec.h b/main/boards/esp-hi/adc_pdm_audio_codec.h new file mode 100644 index 0000000..8c9e836 --- /dev/null +++ b/main/boards/esp-hi/adc_pdm_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _BOX_AUDIO_CODEC_H +#define _BOX_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include +#include + +class AdcPdmAudioCodec : public AudioCodec { +private: + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + gpio_num_t pa_ctrl_pin_ = GPIO_NUM_NC; + + // 定时器相关成员变量 + esp_timer_handle_t output_timer_ = nullptr; + static constexpr uint64_t TIMER_TIMEOUT_US = 120000; // 120ms = 120000us + + // 定时器回调函数 + static void OutputTimerCallback(void* arg); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + AdcPdmAudioCodec(int input_sample_rate, int output_sample_rate, + uint32_t adc_mic_channel, gpio_num_t pdm_speak_p, gpio_num_t pdm_speak_n, gpio_num_t pa_ctl); + virtual ~AdcPdmAudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; + void Start(); +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/esp-hi/config.h b/main/boards/esp-hi/config.h new file mode 100644 index 0000000..8ea4ffc --- /dev/null +++ b/main/boards/esp-hi/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 配置PDM上采样fs参数(取值范围<=480)。部分设备在441时表现更稳定 +#define AUDIO_PDM_UPSAMPLE_FS 441 + +#define AUDIO_ADC_MIC_CHANNEL 2 +#define AUDIO_PDM_SPEAK_P_GPIO GPIO_NUM_6 +#define AUDIO_PDM_SPEAK_N_GPIO GPIO_NUM_7 +#define AUDIO_PA_CTL_GPIO GPIO_NUM_3 + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_9 +#define MOVE_WAKE_BUTTON_GPIO GPIO_NUM_0 +#define AUDIO_WAKE_BUTTON_GPIO GPIO_NUM_1 + +#define DISPLAY_MOSI_PIN GPIO_NUM_4 +#define DISPLAY_CLK_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_10 +#define DISPLAY_RST_PIN GPIO_NUM_NC +#define DISPLAY_CS_PIN GPIO_NUM_NC + +#define FL_GPIO_NUM GPIO_NUM_21 +#define FR_GPIO_NUM GPIO_NUM_19 +#define BL_GPIO_NUM GPIO_NUM_20 +#define BR_GPIO_NUM GPIO_NUM_18 + +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 160 +#define DISPLAY_HEIGHT 80 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true + +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-hi/config.json b/main/boards/esp-hi/config.json new file mode 100644 index 0000000..e136eaf --- /dev/null +++ b/main/boards/esp-hi/config.json @@ -0,0 +1,33 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "esp-hi", + "sdkconfig_append": [ + "CONFIG_IDF_TARGET=\"esp32c3\"", + "CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/4m.csv\"", + "CONFIG_ESP_WIFI_STATIC_RX_BUFFER_NUM=3", + "CONFIG_ESP_WIFI_DYNAMIC_RX_BUFFER_NUM=4", + "CONFIG_ESP_WIFI_AMPDU_TX_ENABLED=n", + "CONFIG_ESP_WIFI_RX_BA_WIN=4", + "CONFIG_ESP_WIFI_ENABLE_WPA3_SAE=n", + "CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=0", + "CONFIG_ESP_WIFI_ENTERPRISE_SUPPORT=n", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y", + "CONFIG_ESP_MAIN_TASK_STACK_SIZE=7168", + "CONFIG_FREERTOS_HZ=1000", + "CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=768", + "CONFIG_LWIP_MAX_SOCKETS=10", + "CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=16", + "CONFIG_LWIP_IPV6=n", + "CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=2048", + "CONFIG_MBEDTLS_DYNAMIC_FREE_CONFIG_DATA=y", + "CONFIG_NEWLIB_NANO_FORMAT=y", + "CONFIG_ESP_CONSOLE_NONE=y", + "CONFIG_USE_ESP_WAKE_WORD=y", + "CONFIG_COMPILER_OPTIMIZATION_SIZE=y" + ] + } + ] +} diff --git a/main/boards/esp-hi/emoji_display.cc b/main/boards/esp-hi/emoji_display.cc new file mode 100644 index 0000000..c494337 --- /dev/null +++ b/main/boards/esp-hi/emoji_display.cc @@ -0,0 +1,178 @@ +#include +#include "display/lcd_display.h" +#include +#include "emoji_display.h" +#include "assets/lang_config.h" +#include "assets.h" + +#include +#include +#include +#include +#include + +static const char *TAG = "emoji"; + +namespace anim { + +// Emoji asset name mapping based on usage pattern +static const std::unordered_map emoji_asset_name_map = { + {"connecting", "connecting.aaf"}, + {"wake", "wake.aaf"}, + {"asking", "asking.aaf"}, + {"happy_loop", "happy_loop.aaf"}, + {"sad_loop", "sad_loop.aaf"}, + {"anger_loop", "anger_loop.aaf"}, + {"panic_loop", "panic_loop.aaf"}, + {"blink_quick", "blink_quick.aaf"}, + {"scorn_loop", "scorn_loop.aaf"} +}; + +bool EmojiPlayer::OnFlushIoReady(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t *edata, void *user_ctx) +{ + auto* disp_drv = static_cast(user_ctx); + anim_player_flush_ready(disp_drv); + return true; +} + +void EmojiPlayer::OnFlush(anim_player_handle_t handle, int x_start, int y_start, int x_end, int y_end, const void *color_data) +{ + auto* panel = static_cast(anim_player_get_user_data(handle)); + esp_lcd_panel_draw_bitmap(panel, x_start, y_start, x_end, y_end, color_data); +} + +EmojiPlayer::EmojiPlayer(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io) +{ + ESP_LOGI(TAG, "Create EmojiPlayer, panel: %p, panel_io: %p", panel, panel_io); + + anim_player_config_t player_cfg = { + .flush_cb = OnFlush, + .update_cb = NULL, + .user_data = panel, + .flags = {.swap = true}, + .task = ANIM_PLAYER_INIT_CONFIG() + }; + + player_cfg.task.task_priority = 1; + player_cfg.task.task_stack = 4096; + player_handle_ = anim_player_init(&player_cfg); + + const esp_lcd_panel_io_callbacks_t cbs = { + .on_color_trans_done = OnFlushIoReady, + }; + esp_lcd_panel_io_register_event_callbacks(panel_io, &cbs, player_handle_); + StartPlayer("connecting", true, 15); +} + +EmojiPlayer::~EmojiPlayer() +{ + if (player_handle_) { + anim_player_update(player_handle_, PLAYER_ACTION_STOP); + anim_player_deinit(player_handle_); + player_handle_ = nullptr; + } +} + +void EmojiPlayer::StartPlayer(const std::string& asset_name, bool repeat, int fps) +{ + if (player_handle_) { + uint32_t start, end; + void *src_data = nullptr; + size_t src_len = 0; + + auto& assets = Assets::GetInstance(); + std::string filename = emoji_asset_name_map.at(asset_name); + if (!assets.GetAssetData(filename, src_data, src_len)) { + ESP_LOGE(TAG, "Failed to get asset data for %s", asset_name.c_str()); + return; + } + + anim_player_set_src_data(player_handle_, src_data, src_len); + anim_player_get_segment(player_handle_, &start, &end); + if(asset_name == "wake"){ + start = 7; + } + anim_player_set_segment(player_handle_, start, end, fps, true); + anim_player_update(player_handle_, PLAYER_ACTION_START); + } +} + +void EmojiPlayer::StopPlayer() +{ + if (player_handle_) { + anim_player_update(player_handle_, PLAYER_ACTION_STOP); + } +} + +EmojiWidget::EmojiWidget(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io) +{ + InitializePlayer(panel, panel_io); +} + +EmojiWidget::~EmojiWidget() +{ + +} + +void EmojiWidget::SetEmotion(const char* emotion) +{ + if (!player_) { + return; + } + + using Param = std::tuple; + static const std::unordered_map emotion_map = { + {"happy", {"happy_loop", true, 25}}, + {"laughing", {"happy_loop", true, 25}}, + {"funny", {"happy_loop", true, 25}}, + {"loving", {"happy_loop", true, 25}}, + {"embarrassed", {"happy_loop", true, 25}}, + {"confident", {"happy_loop", true, 25}}, + {"delicious", {"happy_loop", true, 25}}, + {"sad", {"sad_loop", true, 25}}, + {"crying", {"sad_loop", true, 25}}, + {"sleepy", {"sad_loop", true, 25}}, + {"silly", {"sad_loop", true, 25}}, + {"angry", {"anger_loop", true, 25}}, + {"surprised", {"panic_loop", true, 25}}, + {"shocked", {"panic_loop", true, 25}}, + {"thinking", {"happy_loop", true, 25}}, + {"winking", {"blink_quick", true, 5}}, + {"relaxed", {"scorn_loop", true, 25}}, + {"confused", {"scorn_loop", true, 25}}, + }; + + auto it = emotion_map.find(emotion); + if (it != emotion_map.end()) { + const auto& [aaf, repeat, fps] = it->second; + player_->StartPlayer(aaf, repeat, fps); + } else if (strcmp(emotion, "neutral") == 0) { + } +} + +void EmojiWidget::SetStatus(const char* status) +{ + if (player_) { + if (strcmp(status, Lang::Strings::LISTENING) == 0) { + player_->StartPlayer("asking", true, 15); + } else if (strcmp(status, Lang::Strings::STANDBY) == 0) { + player_->StartPlayer("wake", true, 15); + } + } +} + +void EmojiWidget::InitializePlayer(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io) +{ + player_ = std::make_unique(panel, panel_io); +} + +bool EmojiWidget::Lock(int timeout_ms) +{ + return true; +} + +void EmojiWidget::Unlock() +{ +} + +} // namespace anim diff --git a/main/boards/esp-hi/emoji_display.h b/main/boards/esp-hi/emoji_display.h new file mode 100644 index 0000000..d4faab7 --- /dev/null +++ b/main/boards/esp-hi/emoji_display.h @@ -0,0 +1,55 @@ +#pragma once + +#include "display/lcd_display.h" +#include +#include +#include +#include +#include "anim_player.h" +#include "assets.h" + +namespace anim { + +class EmojiPlayer; + +using FlushIoReadyCallback = std::function; +using FlushCallback = std::function; + +class EmojiPlayer { +public: + EmojiPlayer(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io); + ~EmojiPlayer(); + + void StartPlayer(const std::string& asset_name, bool repeat, int fps); + void StopPlayer(); + +private: + static bool OnFlushIoReady(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t *edata, void *user_ctx); + static void OnFlush(anim_player_handle_t handle, int x_start, int y_start, int x_end, int y_end, const void *color_data); + + anim_player_handle_t player_handle_; +}; + +class EmojiWidget : public Display { +public: + EmojiWidget(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io); + virtual ~EmojiWidget(); + + virtual void SetEmotion(const char* emotion) override; + virtual void SetStatus(const char* status) override; + virtual void SetChatMessage(const char* role, const char* content) override {} + + anim::EmojiPlayer* GetPlayer() + { + return player_.get(); + } + +private: + void InitializePlayer(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io); + virtual bool Lock(int timeout_ms = 0) override; + virtual void Unlock() override; + + std::unique_ptr player_; +}; + +} // namespace anim diff --git a/main/boards/esp-hi/esp_hi.cc b/main/boards/esp-hi/esp_hi.cc new file mode 100644 index 0000000..0da56a4 --- /dev/null +++ b/main/boards/esp-hi/esp_hi.cc @@ -0,0 +1,420 @@ +#include "wifi_board.h" +#include "adc_pdm_audio_codec.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include +#include +#include +#include +#include +#include + +#include "display/lcd_display.h" +#include +#include +#include +#include "esp_lcd_ili9341.h" + +#include "assets/lang_config.h" +#include "anim_player.h" +#include "emoji_display.h" +#include "servo_dog_ctrl.h" +#include "led_strip.h" +#include "driver/rmt_tx.h" +#include "device_state_event.h" + +#include "sdkconfig.h" + +#ifdef CONFIG_ESP_HI_WEB_CONTROL_ENABLED +#include "esp_hi_web_control.h" +#endif //CONFIG_ESP_HI_WEB_CONTROL_ENABLED + +#define TAG "ESP_HI" + +static const ili9341_lcd_init_cmd_t vendor_specific_init[] = { + {0x11, NULL, 0, 120}, // Sleep out, Delay 120ms + {0xB1, (uint8_t []){0x05, 0x3A, 0x3A}, 3, 0}, + {0xB2, (uint8_t []){0x05, 0x3A, 0x3A}, 3, 0}, + {0xB3, (uint8_t []){0x05, 0x3A, 0x3A, 0x05, 0x3A, 0x3A}, 6, 0}, + {0xB4, (uint8_t []){0x03}, 1, 0}, // Dot inversion + {0xC0, (uint8_t []){0x44, 0x04, 0x04}, 3, 0}, + {0xC1, (uint8_t []){0xC0}, 1, 0}, + {0xC2, (uint8_t []){0x0D, 0x00}, 2, 0}, + {0xC3, (uint8_t []){0x8D, 0x6A}, 2, 0}, + {0xC4, (uint8_t []){0x8D, 0xEE}, 2, 0}, + {0xC5, (uint8_t []){0x08}, 1, 0}, + {0xE0, (uint8_t []){0x0F, 0x10, 0x03, 0x03, 0x07, 0x02, 0x00, 0x02, 0x07, 0x0C, 0x13, 0x38, 0x0A, 0x0E, 0x03, 0x10}, 16, 0}, + {0xE1, (uint8_t []){0x10, 0x0B, 0x04, 0x04, 0x10, 0x03, 0x00, 0x03, 0x03, 0x09, 0x17, 0x33, 0x0B, 0x0C, 0x06, 0x10}, 16, 0}, + {0x35, (uint8_t []){0x00}, 1, 0}, + {0x3A, (uint8_t []){0x05}, 1, 0}, + {0x36, (uint8_t []){0xC8}, 1, 0}, + {0x29, NULL, 0, 0}, // Display on + {0x2C, NULL, 0, 0}, // Memory write +}; + +static const led_strip_config_t bsp_strip_config = { + .strip_gpio_num = GPIO_NUM_8, + .max_leds = 4, + .led_model = LED_MODEL_WS2812, + .flags = { + .invert_out = false + } +}; + +static const led_strip_rmt_config_t bsp_rmt_config = { + .clk_src = RMT_CLK_SRC_DEFAULT, + .resolution_hz = 10 * 1000 * 1000, + .flags = { + .with_dma = false + } +}; + +class EspHi : public WifiBoard { +private: + Button boot_button_; + Button audio_wake_button_; + Button move_wake_button_; + anim::EmojiWidget* display_ = nullptr; + bool web_server_initialized_ = false; + led_strip_handle_t led_strip_; + bool led_on_ = false; + +#ifdef CONFIG_ESP_HI_WEB_CONTROL_ENABLED + static void wifi_event_handler(void* arg, esp_event_base_t event_base, + int32_t event_id, void* event_data) + { + if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_CONNECTED) { + + xTaskCreate( + [](void* arg) { + EspHi* instance = static_cast(arg); + + vTaskDelay(5000 / portTICK_PERIOD_MS); + + if (!instance->web_server_initialized_) { + ESP_LOGI(TAG, "WiFi connected, init web control server"); + esp_err_t err = esp_hi_web_control_server_init(); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize web control server: %d", err); + } else { + ESP_LOGI(TAG, "Web control server initialized"); + instance->web_server_initialized_ = true; + } + } + + vTaskDelete(NULL); + }, + "web_server_init", + 1024 * 10, arg, 5, nullptr); + } + } +#endif //CONFIG_ESP_HI_WEB_CONTROL_ENABLED + + void HandleMoveWakePressDown(int64_t current_time, int64_t &last_trigger_time, int &gesture_state) + { + int64_t interval = last_trigger_time == 0 ? 0 : current_time - last_trigger_time; + last_trigger_time = current_time; + + if (interval > 1000) { + gesture_state = 0; + } else { + switch (gesture_state) { + case 0: + break; + case 1: + if (interval > 300) { + gesture_state = 2; + } + break; + case 2: + if (interval > 100) { + gesture_state = 0; + } + break; + } + } + } + + void HandleMoveWakePressUp(int64_t current_time, int64_t &last_trigger_time, int &gesture_state) + { + int64_t interval = current_time - last_trigger_time; + + if (interval > 1000) { + gesture_state = 0; + } else { + switch (gesture_state) { + case 0: + if (interval > 300) { + gesture_state = 1; + } + break; + case 1: + break; + case 2: + if (interval < 100) { + ESP_LOGI(TAG, "gesture detected"); + gesture_state = 0; + auto &app = Application::GetInstance(); + app.ToggleChatState(); + } + break; + } + } + } + + void InitializeButtons() + { + static int64_t last_trigger_time = 0; + static int gesture_state = 0; // 0: init, 1: wait second long interval, 2: wait oscillation + + boot_button_.OnClick([this]() { + auto &app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + audio_wake_button_.OnPressDown([this]() { + }); + + audio_wake_button_.OnPressUp([this]() { + }); + + move_wake_button_.OnPressDown([this]() { + int64_t current_time = esp_timer_get_time() / 1000; + HandleMoveWakePressDown(current_time, last_trigger_time, gesture_state); + }); + + move_wake_button_.OnPressUp([this]() { + int64_t current_time = esp_timer_get_time() / 1000; + HandleMoveWakePressUp(current_time, last_trigger_time, gesture_state); + }); + } + + void InitializeLed() { + ESP_LOGI(TAG, "BLINK_GPIO setting %d", bsp_strip_config.strip_gpio_num); + + ESP_ERROR_CHECK(led_strip_new_rmt_device(&bsp_strip_config, &bsp_rmt_config, &led_strip_)); + led_strip_set_pixel(led_strip_, 0, 0x00, 0x00, 0x00); + led_strip_set_pixel(led_strip_, 1, 0x00, 0x00, 0x00); + led_strip_set_pixel(led_strip_, 2, 0x00, 0x00, 0x00); + led_strip_set_pixel(led_strip_, 3, 0x00, 0x00, 0x00); + led_strip_refresh(led_strip_); + } + + esp_err_t SetLedColor(uint8_t r, uint8_t g, uint8_t b) { + esp_err_t ret = ESP_OK; + + ret |= led_strip_set_pixel(led_strip_, 0, r, g, b); + ret |= led_strip_set_pixel(led_strip_, 1, r, g, b); + ret |= led_strip_set_pixel(led_strip_, 2, r, g, b); + ret |= led_strip_set_pixel(led_strip_, 3, r, g, b); + ret |= led_strip_refresh(led_strip_); + return ret; + } + + void InitializeIot() + { + ESP_LOGI(TAG, "Initialize Iot"); + InitializeLed(); + SetLedColor(0x00, 0x00, 0x00); + +#ifdef CONFIG_ESP_HI_WEB_CONTROL_ENABLED + ESP_ERROR_CHECK(esp_event_handler_register(WIFI_EVENT, WIFI_EVENT_STA_CONNECTED, + &wifi_event_handler, this)); +#endif //CONFIG_ESP_HI_WEB_CONTROL_ENABLED + } + + void InitializeSpi() + { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * 10 * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() + { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const ili9341_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(ili9341_lcd_init_cmd_t), + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *) &vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_set_gap(panel, 0, 24); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + ESP_LOGI(TAG, "LCD panel create success, %p", panel); + + esp_lcd_panel_disp_on_off(panel, true); + + ESP_LOGI(TAG, "Create emoji widget, panel: %p, panel_io: %p", panel, panel_io); + display_ = new anim::EmojiWidget(panel, panel_io); + +#if CONFIG_ESP_CONSOLE_NONE + servo_dog_ctrl_config_t config = { + .fl_gpio_num = FL_GPIO_NUM, + .fr_gpio_num = FR_GPIO_NUM, + .bl_gpio_num = BL_GPIO_NUM, + .br_gpio_num = BR_GPIO_NUM, + }; + + servo_dog_ctrl_init(&config); +#endif + } + + void InitializeTools() + { + auto& mcp_server = McpServer::GetInstance(); + + // 基础动作控制 + mcp_server.AddTool("self.dog.basic_control", "机器人的基础动作。机器人可以做以下基础动作:\n" + "forward: 向前移动\nbackward: 向后移动\nturn_left: 向左转\nturn_right: 向右转\nstop: 立即停止当前动作", + PropertyList({ + Property("action", kPropertyTypeString), + }), [this](const PropertyList& properties) -> ReturnValue { + const std::string& action = properties["action"].value(); + if (action == "forward") { + servo_dog_ctrl_send(DOG_STATE_FORWARD, NULL); + } else if (action == "backward") { + servo_dog_ctrl_send(DOG_STATE_BACKWARD, NULL); + } else if (action == "turn_left") { + servo_dog_ctrl_send(DOG_STATE_TURN_LEFT, NULL); + } else if (action == "turn_right") { + servo_dog_ctrl_send(DOG_STATE_TURN_RIGHT, NULL); + } else if (action == "stop") { + servo_dog_ctrl_send(DOG_STATE_IDLE, NULL); + } else { + return false; + } + return true; + }); + + // 扩展动作控制 + mcp_server.AddTool("self.dog.advanced_control", "机器人的扩展动作。机器人可以做以下扩展动作:\n" + "sway_back_forth: 前后摇摆\nlay_down: 趴下\nsway: 左右摇摆\nretract_legs: 收回腿部\n" + "shake_hand: 握手\nshake_back_legs: 伸懒腰\njump_forward: 向前跳跃", + PropertyList({ + Property("action", kPropertyTypeString), + }), [this](const PropertyList& properties) -> ReturnValue { + const std::string& action = properties["action"].value(); + if (action == "sway_back_forth") { + servo_dog_ctrl_send(DOG_STATE_SWAY_BACK_FORTH, NULL); + } else if (action == "lay_down") { + servo_dog_ctrl_send(DOG_STATE_LAY_DOWN, NULL); + } else if (action == "sway") { + dog_action_args_t args = { + .repeat_count = 4, + }; + servo_dog_ctrl_send(DOG_STATE_SWAY, &args); + } else if (action == "retract_legs") { + servo_dog_ctrl_send(DOG_STATE_RETRACT_LEGS, NULL); + } else if (action == "shake_hand") { + servo_dog_ctrl_send(DOG_STATE_SHAKE_HAND, NULL); + } else if (action == "shake_back_legs") { + servo_dog_ctrl_send(DOG_STATE_SHAKE_BACK_LEGS, NULL); + } else if (action == "jump_forward") { + servo_dog_ctrl_send(DOG_STATE_JUMP_FORWARD, NULL); + } else { + return false; + } + return true; + }); + + // 灯光控制 + mcp_server.AddTool("self.light.get_power", "获取灯是否打开", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return led_on_; + }); + + mcp_server.AddTool("self.light.turn_on", "打开灯", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SetLedColor(0xFF, 0xFF, 0xFF); + led_on_ = true; + return true; + }); + + mcp_server.AddTool("self.light.turn_off", "关闭灯", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SetLedColor(0x00, 0x00, 0x00); + led_on_ = false; + return true; + }); + + mcp_server.AddTool("self.light.set_rgb", "设置RGB颜色", PropertyList({ + Property("r", kPropertyTypeInteger, 0, 255), + Property("g", kPropertyTypeInteger, 0, 255), + Property("b", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int r = properties["r"].value(); + int g = properties["g"].value(); + int b = properties["b"].value(); + + led_on_ = true; + SetLedColor(r, g, b); + return true; + }); + } + +public: + EspHi() : boot_button_(BOOT_BUTTON_GPIO), + audio_wake_button_(AUDIO_WAKE_BUTTON_GPIO), + move_wake_button_(MOVE_WAKE_BUTTON_GPIO) + { + InitializeButtons(); + InitializeIot(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override + { + static AdcPdmAudioCodec audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_ADC_MIC_CHANNEL, + AUDIO_PDM_SPEAK_P_GPIO, + AUDIO_PDM_SPEAK_N_GPIO, + AUDIO_PA_CTL_GPIO); + return &audio_codec; + } + + virtual Display* GetDisplay() override + { + return display_; + } +}; + +DECLARE_BOARD(EspHi); diff --git a/main/boards/esp-p4-function-ev-board/README.md b/main/boards/esp-p4-function-ev-board/README.md new file mode 100644 index 0000000..5fde9b2 --- /dev/null +++ b/main/boards/esp-p4-function-ev-board/README.md @@ -0,0 +1,41 @@ +# ESP-P4-Function-EV-Board + +Board support for ESP-P4-Function-EV-Board. Wi‑Fi uses ESP‑Hosted via the on‑board ESP32‑C6. LCD is supported via the official MIPI‑DSI LCD adapter. + +## Features +- Wi‑Fi: `esp_wifi_remote` + `esp_hosted` (SDIO) with ESP32‑C6 co‑processor +- Display: 7" MIPI‑DSI LCD (1024×600) via adapter; can also run headless +- Audio: ES8311 codec with speaker and microphone support +- Touch: GT911 capacitive touch controller +- SD Card: MicroSD card support (MMC mode) +- Camera: MIPI-CSI camera interface with fallback DVP configuration (OV5647, SC2336 sensors supported) +- USB: USB host/device support +- SPIFFS: Built-in flash filesystem support +- Fonts: Custom font support with Unicode characters (Vietnamese, Chinese, etc.) + +## Configure +In `menuconfig`: Xiaozhi Assistant -> Board Type -> ESP-P4-Function-EV-Board + +Ensure these are set (auto-set when building via config.json): +- `CONFIG_SLAVE_IDF_TARGET_ESP32C6=y` +- `CONFIG_ESP_HOSTED_P4_DEV_BOARD_FUNC_BOARD=y` +- `CONFIG_ESP_HOSTED_SDIO_HOST_INTERFACE=y` +- `CONFIG_ESP_HOSTED_SDIO_4_BIT_BUS=y` + +## LCD Connection (from Espressif user guide) +- Connect the LCD adapter board J3 to the board’s MIPI DSI connector (reverse ribbon). +- Wire `RST_LCD` (adapter J6) to `GPIO27` (board J1). +- Wire `PWM` (adapter J6) to `GPIO26` (board J1). +- Optionally power the LCD adapter via its USB or provide `5V` and `GND` from the board. + +These pins are pre-configured in `config.h` as `PIN_NUM_LCD_RST=GPIO27` and `DISPLAY_BACKLIGHT_PIN=GPIO26`. Resolution is set to 1024×600. + +## Build (example) +```powershell +idf.py set-target esp32p4 +idf.py menuconfig +idf.py build +``` + +Tip: In menuconfig, choose Xiaozhi Assistant -> Board Type -> ESP-P4-Function-EV-Board. +If building a release via scripts, the `config.json` in this folder appends the required Hosted options. diff --git a/main/boards/esp-p4-function-ev-board/config.h b/main/boards/esp-p4-function-ev-board/config.h new file mode 100644 index 0000000..aca0c93 --- /dev/null +++ b/main/boards/esp-p4-function-ev-board/config.h @@ -0,0 +1,11 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include "bsp/esp32_p4_function_ev_board.h" // Library for board configs and pins + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ \ No newline at end of file diff --git a/main/boards/esp-p4-function-ev-board/config.json b/main/boards/esp-p4-function-ev-board/config.json new file mode 100644 index 0000000..d191f94 --- /dev/null +++ b/main/boards/esp-p4-function-ev-board/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "esp-p4-function-ev-board", + "sdkconfig_append": [ + "CONFIG_SLAVE_IDF_TARGET_ESP32C6=y", + "CONFIG_ESP_HOSTED_P4_DEV_BOARD_FUNC_BOARD=y", + "CONFIG_ESP_HOSTED_SDIO_HOST_INTERFACE=y", + "CONFIG_ESP_HOSTED_SDIO_4_BIT_BUS=y", + "CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y", + "CONFIG_BSP_LCD_TYPE_1024_600=y" + ] + } + ] +} diff --git a/main/boards/esp-p4-function-ev-board/esp-p4-function-ev-board.cc b/main/boards/esp-p4-function-ev-board/esp-p4-function-ev-board.cc new file mode 100644 index 0000000..82c00cf --- /dev/null +++ b/main/boards/esp-p4-function-ev-board/esp-p4-function-ev-board.cc @@ -0,0 +1,232 @@ +#include "wifi_board.h" +#include "audio/codecs/es8311_audio_codec.h" +// Display +#include "display/display.h" +#include "display/lcd_display.h" +#include "lvgl_theme.h" +// Backlight +// PwmBacklight is declared in backlight headers pulled by display/lcd_display includes via lvgl stack + +#include "application.h" +#include "button.h" +#include "config.h" +#include "esp32_camera.h" + +#include +#include +#include +#include +#include +#include +// SD card +#include +#include +#include +#include +// SD power control (on-chip LDO) +#include "sd_pwr_ctrl_by_on_chip_ldo.h" + +// MIPI-DSI / LCD vendor includes (library may replace some) +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" +#include "esp_lcd_ek79007.h" +#include "esp_lcd_touch_gt911.h" + +// Library includes +#include "bsp/esp32_p4_function_ev_board.h" +#include "bsp/touch.h" + +#define TAG "ESP32P4FuncEV" + +class ESP32P4FunctionEvBoard : public WifiBoard +{ +private: + i2c_master_bus_handle_t codec_i2c_bus_ = nullptr; + Button boot_button_; + LcdDisplay *display_ = nullptr; + esp_lcd_touch_handle_t tp_ = nullptr; + Esp32Camera* camera_ = nullptr; + + void InitializeI2cBuses() + { + ESP_ERROR_CHECK(bsp_i2c_init()); + codec_i2c_bus_ = bsp_i2c_get_handle(); + } + + // Touch I2C bus initialization is not required for this board (handled elsewhere) + void InitializeTouchI2cBus() + { + // No implementation needed + } + + void InitializeLCD() + { + bsp_display_config_t config = { + .hdmi_resolution = BSP_HDMI_RES_NONE, + .dsi_bus = { + .phy_clk_src = (mipi_dsi_phy_clock_source_t)SOC_MOD_CLK_PLL_F20M, + .lane_bit_rate_mbps = 1000, + }, + }; + + bsp_lcd_handles_t handles; + ESP_ERROR_CHECK(bsp_display_new_with_handles(&config, &handles)); + + display_ = new MipiLcdDisplay(handles.io, handles.panel, 1024, 600, 0, 0, true, true, false); + } + + void InitializeButtons() + { + boot_button_.OnClick([this]() + { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + + void InitializeTouch() + { + ESP_ERROR_CHECK(bsp_touch_new(NULL, &tp_)); + } + + void InitializeSdCard() + { + ESP_LOGI(TAG, "Initializing SD card"); + esp_err_t ret = bsp_sdcard_mount(); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to mount SD card: %s", esp_err_to_name(ret)); + } else { + ESP_LOGI(TAG, "SD card mounted successfully"); + } + } + + void InitializeCamera() + { + ESP_LOGI(TAG, "Initializing camera"); + + // Use BSP camera initialization for ESP-P4 + bsp_camera_cfg_t camera_cfg = {0}; + esp_err_t ret = bsp_camera_start(&camera_cfg); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize BSP camera: %s", esp_err_to_name(ret)); + ESP_LOGI(TAG, "Attempting alternative camera initialization"); + + // Alternative: Direct Esp32Camera initialization if BSP fails + // This provides more control over camera configuration + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = BSP_I2C_SDA, // Reuse I2C pins if camera pins not defined + [1] = BSP_I2C_SCL, + [2] = GPIO_NUM_NC, + [3] = GPIO_NUM_NC, + [4] = GPIO_NUM_NC, + [5] = GPIO_NUM_NC, + [6] = GPIO_NUM_NC, + [7] = GPIO_NUM_NC, + }, + .vsync_io = GPIO_NUM_NC, + .de_io = GPIO_NUM_NC, + .pclk_io = GPIO_NUM_NC, + .xclk_io = GPIO_NUM_NC, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, // Use existing I2C bus + .i2c_handle = codec_i2c_bus_, // Reuse the existing I2C bus + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + .dvp_pin = dvp_pin_config, + .xclk_freq = 20000000, // 20MHz typical for cameras + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + // Try to create camera with direct configuration + camera_ = new Esp32Camera(video_config); + ESP_LOGI(TAG, "Camera initialized with direct configuration"); + } else { + ESP_LOGI(TAG, "Camera initialized successfully via BSP"); + } + } + + void InitializeFonts() + { + ESP_LOGI(TAG, "Initializing font support"); + // Font initialization is handled by the Assets system + // The board supports loading fonts from assets partition + // Verify that fonts are properly loaded by checking theme + auto& theme_manager = LvglThemeManager::GetInstance(); + auto current_theme = theme_manager.GetTheme("light"); + if (current_theme != nullptr) { + auto text_font = current_theme->text_font(); + if (text_font != nullptr && text_font->font() != nullptr) { + ESP_LOGI(TAG, "Custom font loaded successfully: line_height=%d", text_font->font()->line_height); + } else { + ESP_LOGW(TAG, "Custom font not loaded, using built-in font"); + } + } + } + +public: + + ESP32P4FunctionEvBoard() : boot_button_(0) + { + InitializeI2cBuses(); + // Audio is initialized by Es8311AudioCodec + InitializeLCD(); + InitializeButtons(); + InitializeTouch(); + InitializeSdCard(); + InitializeCamera(); + InitializeFonts(); + GetBacklight()->RestoreBrightness(); + } + + ~ESP32P4FunctionEvBoard() + { + // Clean up display pointer + delete display_; + display_ = nullptr; + // Unmount SD card + esp_err_t ret = bsp_sdcard_unmount(); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to unmount SD card: %s", esp_err_to_name(ret)); + } + // If other resources need cleanup, add here + } + + virtual AudioCodec *GetAudioCodec() override + { + static Es8311AudioCodec audio_codec( + codec_i2c_bus_, (i2c_port_t)BSP_I2C_NUM, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + BSP_I2S_MCLK, BSP_I2S_SCLK, BSP_I2S_LCLK, BSP_I2S_DOUT, BSP_I2S_DSIN, + BSP_POWER_AMP_IO, ES8311_CODEC_DEFAULT_ADDR, true, false); + return &audio_codec; + } + + virtual Display *GetDisplay() override { return display_; } + + virtual Backlight *GetBacklight() override + { + static PwmBacklight backlight(BSP_LCD_BACKLIGHT, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual Camera *GetCamera() override + { + return camera_; + } +}; + +DECLARE_BOARD(ESP32P4FunctionEvBoard); diff --git a/main/boards/esp-s3-lcd-ev-board-2/README.md b/main/boards/esp-s3-lcd-ev-board-2/README.md new file mode 100644 index 0000000..5fcacc4 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/README.md @@ -0,0 +1,10 @@ +请确认自己的开发板硬件版本,如果硬件版本,在配置中进行ev_board type进行选择 +1.4与1.5只有io进行变更 +可以查看官方文档,确认具体细节https://docs.espressif.com/projects/esp-dev-kits/en/latest/esp32s3/esp32-s3-lcd-ev-board/user_guide.html +具体调整为: +I2C_SCL IO18 -> IO48 +I2C_SDA IO8 -> IO47 +LCD_DATA6 IO47 -> IO8 +LCD_DATA7 IO48 -> IO18 + +本版本只支持了800x480的屏幕 \ No newline at end of file diff --git a/main/boards/esp-s3-lcd-ev-board-2/config.h b/main/boards/esp-s3-lcd-ev-board-2/config.h new file mode 100644 index 0000000..a59cf05 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/config.h @@ -0,0 +1,42 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_7 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_6 + +#define BSP_POWER_AMP_IO (IO_EXPANDER_PIN_NUM_0) +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 + +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR 0x82 + + +#define BUILTIN_LED_GPIO GPIO_NUM_4 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_WIDTH 800 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_19 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-s3-lcd-ev-board-2/config.json b/main/boards/esp-s3-lcd-ev-board-2/config.json new file mode 100644 index 0000000..27ab752 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-s3-lcd-ev-board-2", + "sdkconfig_append": [] + } + ] +} diff --git a/main/boards/esp-s3-lcd-ev-board-2/esp-s3-lcd-ev-board-2.cc b/main/boards/esp-s3-lcd-ev-board-2/esp-s3-lcd-ev-board-2.cc new file mode 100644 index 0000000..8dc6585 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/esp-s3-lcd-ev-board-2.cc @@ -0,0 +1,235 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "pin_config.h" + +#include "config.h" + +#include +#include +#include +#include "esp_lcd_gc9503.h" +#include +#include +#include +#include +#include +#include +#include + +#define TAG "ESP_S3_LCD_EV_Board_2" + +class ESP_S3_LCD_EV_Board_2 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + //add support ev board lcd + esp_io_expander_handle_t expander = NULL; + + void InitializeRGB_GC9503V_Display() { + ESP_LOGI(TAG, "Init GC9503V"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + + // add support ev board lcd + gpio_config_t io_conf = { + .pin_bit_mask = BIT64(GC9503V_PIN_NUM_VSYNC), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_ENABLE, + }; + + gpio_config(&io_conf); + gpio_set_level(GC9503V_PIN_NUM_VSYNC, 1); + + ESP_LOGI(TAG, "Install 3-wire SPI panel IO"); + spi_line_config_t line_config = { + .cs_io_type = IO_TYPE_EXPANDER, + .cs_expander_pin = GC9503V_LCD_IO_SPI_CS_1, + .scl_io_type = IO_TYPE_EXPANDER, + .scl_expander_pin = GC9503V_LCD_IO_SPI_SCL_1, + .sda_io_type = IO_TYPE_EXPANDER, + .sda_expander_pin = GC9503V_LCD_IO_SPI_SDO_1, + .io_expander = expander, + }; + + esp_lcd_panel_io_3wire_spi_config_t io_config = GC9503_PANEL_IO_3WIRE_SPI_CONFIG(line_config, 0); + int espok = esp_lcd_new_panel_io_3wire_spi(&io_config, &panel_io); + ESP_LOGI(TAG, "Install 3-wire SPI panel IO:%d",espok); + + ESP_LOGI(TAG, "Install RGB LCD panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_rgb_panel_config_t rgb_config = { + .clk_src = LCD_CLK_SRC_PLL160M, + //add support ev board + .timings = GC9503_800_480_PANEL_60HZ_RGB_TIMING(), + .data_width = 16, // RGB565 in parallel mode, thus 16bit in width + .bits_per_pixel = 16, + .num_fbs = GC9503V_LCD_RGB_BUFFER_NUMS, + .bounce_buffer_size_px = GC9503V_LCD_H_RES * GC9503V_LCD_RGB_BOUNCE_BUFFER_HEIGHT, + .dma_burst_size = 64, + .hsync_gpio_num = GC9503V_PIN_NUM_HSYNC, + .vsync_gpio_num = GC9503V_PIN_NUM_VSYNC, + .de_gpio_num = GC9503V_PIN_NUM_DE, + .pclk_gpio_num = GC9503V_PIN_NUM_PCLK, + .disp_gpio_num = GC9503V_PIN_NUM_DISP_EN, + .data_gpio_nums = { + GC9503V_PIN_NUM_DATA0, + GC9503V_PIN_NUM_DATA1, + GC9503V_PIN_NUM_DATA2, + GC9503V_PIN_NUM_DATA3, + GC9503V_PIN_NUM_DATA4, + GC9503V_PIN_NUM_DATA5, + GC9503V_PIN_NUM_DATA6, + GC9503V_PIN_NUM_DATA7, + GC9503V_PIN_NUM_DATA8, + GC9503V_PIN_NUM_DATA9, + GC9503V_PIN_NUM_DATA10, + GC9503V_PIN_NUM_DATA11, + GC9503V_PIN_NUM_DATA12, + GC9503V_PIN_NUM_DATA13, + GC9503V_PIN_NUM_DATA14, + GC9503V_PIN_NUM_DATA15, + }, + .flags= { + .fb_in_psram = true, // allocate frame buffer in PSRAM + } + }; + + ESP_LOGI(TAG, "Initialize RGB LCD panel"); + + gc9503_vendor_config_t vendor_config = { + .rgb_config = &rgb_config, + .flags = { + .mirror_by_cmd = 0, + .auto_del_panel_io = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = -1, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + // .bits_per_pixel = 16, + //add surpport ev board + .bits_per_pixel = 18, + .vendor_config = &vendor_config, + }; + (esp_lcd_new_panel_gc9503(panel_io, &panel_config, &panel_handle)); + (esp_lcd_panel_reset(panel_handle)); + (esp_lcd_panel_init(panel_handle)); + + display_ = new RgbLcdDisplay(panel_io, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + //add support ev board lcd amp + //初始化扩展io口 + esp_io_expander_new_i2c_tca9554(i2c_bus_, 0x20, &expander); + /* Setup power amplifier pin, set default to enable */ + esp_io_expander_set_dir(expander, BSP_POWER_AMP_IO, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(expander, BSP_POWER_AMP_IO, true); + + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeTouch() { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT1151_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt1151(tp_io_handle, &tp_cfg, &tp)); + + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + } + +public: + ESP_S3_LCD_EV_Board_2() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializeRGB_GC9503V_Display(); + InitializeTouch(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + true); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + //添加彩灯显示状态,如果亮度太暗可以去更改默认亮度值 DEFAULT_BRIGHTNESS 在led的sigle_led.cc中 + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + +}; + +DECLARE_BOARD(ESP_S3_LCD_EV_Board_2); diff --git a/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.c b/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.c new file mode 100644 index 0000000..4db550e --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.c @@ -0,0 +1,504 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "esp_lcd_gc9503.h" + +#define GC9503_CMD_MADCTL (0xB1) // Memory data access control +#define GC9503_CMD_MADCTL_DEFAULT (0x10) // Default value of Memory data access control +#define GC9503_CMD_SS_BIT (1 << 0) // Source driver scan direction, 0: top to bottom, 1: bottom to top +#define GC9503_CMD_GS_BIT (1 << 1) // Gate driver scan direction, 0: left to right, 1: right to left +#define GC9503_CMD_BGR_BIT (1 << 5) // RGB/BGR order, 0: RGB, 1: BGR + +typedef struct +{ + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // Save current value of GC9503_CMD_MADCTL register + uint8_t colmod_val; // Save current value of LCD_CMD_COLMOD register + const gc9503_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + struct + { + unsigned int mirror_by_cmd : 1; + unsigned int auto_del_panel_io : 1; + unsigned int display_on_off_use_cmd : 1; + unsigned int reset_level : 1; + } flags; + // To save the original functions of RGB panel + esp_err_t (*init)(esp_lcd_panel_t *panel); + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*reset)(esp_lcd_panel_t *panel); + esp_err_t (*mirror)(esp_lcd_panel_t *panel, bool x_axis, bool y_axis); + esp_err_t (*disp_on_off)(esp_lcd_panel_t *panel, bool on_off); +} gc9503_panel_t; + +static const char *TAG = "gc9503"; + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503); + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool off); + +esp_err_t esp_lcd_new_panel_gc9503(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + gc9503_vendor_config_t *vendor_config = (gc9503_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->rgb_config, ESP_ERR_INVALID_ARG, TAG, "`verndor_config` and `rgb_config` are necessary"); + ESP_RETURN_ON_FALSE(!vendor_config->flags.auto_del_panel_io || !vendor_config->flags.mirror_by_cmd, + ESP_ERR_INVALID_ARG, TAG, "`mirror_by_cmd` and `auto_del_panel_io` cannot work together"); + + esp_err_t ret = ESP_OK; + gpio_config_t io_conf = {0}; + + gc9503_panel_t *gc9503 = (gc9503_panel_t *)calloc(1, sizeof(gc9503_panel_t)); + ESP_RETURN_ON_FALSE(gc9503, ESP_ERR_NO_MEM, TAG, "no mem for gc9503 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + gc9503->madctl_val = GC9503_CMD_MADCTL_DEFAULT; + switch (panel_dev_config->rgb_ele_order) + { + case LCD_RGB_ELEMENT_ORDER_RGB: + gc9503->madctl_val &= ~GC9503_CMD_BGR_BIT; + break; + case LCD_RGB_ELEMENT_ORDER_BGR: + gc9503->madctl_val |= GC9503_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color element order"); + break; + } + + gc9503->colmod_val = 0; + switch (panel_dev_config->bits_per_pixel) + { + case 16: // RGB565 + gc9503->colmod_val = 0x50; + break; + case 18: // RGB666 + gc9503->colmod_val = 0x60; + break; + case 24: // RGB888 + gc9503->colmod_val = 0x70; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + gc9503->io = io; + gc9503->init_cmds = vendor_config->init_cmds; + gc9503->init_cmds_size = vendor_config->init_cmds_size; + gc9503->reset_gpio_num = panel_dev_config->reset_gpio_num; + gc9503->flags.reset_level = panel_dev_config->flags.reset_active_high; + gc9503->flags.auto_del_panel_io = vendor_config->flags.auto_del_panel_io; + gc9503->flags.mirror_by_cmd = vendor_config->flags.mirror_by_cmd; + gc9503->flags.display_on_off_use_cmd = (vendor_config->rgb_config->disp_gpio_num >= 0) ? 0 : 1; + + if (gc9503->flags.auto_del_panel_io) + { + if (gc9503->reset_gpio_num >= 0) + { // Perform hardware reset + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + } + else + { // Perform software reset + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), err, TAG, "send command failed"); + } + vTaskDelay(pdMS_TO_TICKS(120)); + + /** + * In order to enable the 3-wire SPI interface pins (such as SDA and SCK) to share other pins of the RGB interface + * (such as HSYNC) and save GPIOs, we need to send LCD initialization commands via the 3-wire SPI interface before + * `esp_lcd_new_rgb_panel()` is called. + */ + ESP_GOTO_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), err, TAG, "send init commands failed"); + // After sending the initialization commands, the 3-wire SPI interface can be deleted + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_del(io), err, TAG, "delete panel IO failed"); + gc9503->io = NULL; + ESP_LOGD(TAG, "delete panel IO"); + } + + // Create RGB panel + ESP_GOTO_ON_ERROR(esp_lcd_new_rgb_panel(vendor_config->rgb_config, ret_panel), err, TAG, "create RGB panel failed"); + ESP_LOGD(TAG, "new RGB panel @%p", ret_panel); + + // Save the original functions of RGB panel + gc9503->init = (*ret_panel)->init; + gc9503->del = (*ret_panel)->del; + gc9503->reset = (*ret_panel)->reset; + gc9503->mirror = (*ret_panel)->mirror; + gc9503->disp_on_off = (*ret_panel)->disp_on_off; + // Overwrite the functions of RGB panel + (*ret_panel)->init = panel_gc9503_init; + (*ret_panel)->del = panel_gc9503_del; + (*ret_panel)->reset = panel_gc9503_reset; + (*ret_panel)->mirror = panel_gc9503_mirror; + (*ret_panel)->disp_on_off = panel_gc9503_disp_on_off; + (*ret_panel)->user_data = gc9503; + ESP_LOGD(TAG, "new gc9503 panel @%p", gc9503); + + // ESP_LOGI(TAG, "LCD panel create success, version: %d.%d.%d", ESP_LCD_GC9503_VER_MAJOR, ESP_LCD_GC9503_VER_MINOR, + // ESP_LCD_GC9503_VER_PATCH); + return ESP_OK; + +err: + if (gc9503) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(gc9503); + } + return ret; +} + +// *INDENT-OFF* +// static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { +// // {cmd, { data }, data_size, delay_ms} +// {0x11, (uint8_t []){0x00}, 0, 120}, + +// {0xf0, (uint8_t []){0x55, 0xaa, 0x52, 0x08, 0x00}, 5, 0}, +// {0xf6, (uint8_t []){0x5a, 0x87}, 2, 0}, +// {0xc1, (uint8_t []){0x3f}, 1, 0}, +// {0xc2, (uint8_t []){0x0e}, 1, 0}, +// {0xc6, (uint8_t []){0xf8}, 1, 0}, +// {0xc9, (uint8_t []){0x10}, 1, 0}, +// {0xcd, (uint8_t []){0x25}, 1, 0}, +// {0xf8, (uint8_t []){0x8a}, 1, 0}, +// {0xac, (uint8_t []){0x45}, 1, 0}, +// {0xa0, (uint8_t []){0xdd}, 1, 0}, +// {0xa7, (uint8_t []){0x47}, 1, 0}, +// {0xfa, (uint8_t []){0x00, 0x00, 0x00, 0x04}, 4, 0}, +// {0x86, (uint8_t []){0x99, 0xa3, 0xa3, 0x51}, 4, 0}, +// {0xa3, (uint8_t []){0xee}, 1, 0}, +// {0xfd, (uint8_t []){0x3c, 0x3c, 0x00}, 3, 0}, +// {0x71, (uint8_t []){0x48}, 1, 0}, +// {0x72, (uint8_t []){0x48}, 1, 0}, +// {0x73, (uint8_t []){0x00, 0x44}, 2, 0}, +// {0x97, (uint8_t []){0xee}, 1, 0}, +// {0x83, (uint8_t []){0x93}, 1, 0}, +// {0x9a, (uint8_t []){0x72}, 1, 0}, +// {0x9b, (uint8_t []){0x5a}, 1, 0}, +// {0x82, (uint8_t []){0x2c, 0x2c}, 2, 0}, +// {0x6d, (uint8_t []){0x00, 0x1f, 0x19, 0x1a, 0x10, 0x0e, 0x0c, 0x0a, 0x02, 0x07, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, +// 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x08, 0x01, 0x09, 0x0b, 0x0d, 0x0f, 0x1a, 0x19, 0x1f, 0x00}, 32, 0}, +// {0x64, (uint8_t []){0x38, 0x05, 0x01, 0xdb, 0x03, 0x03, 0x38, 0x04, 0x01, 0xdc, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x65, (uint8_t []){0x38, 0x03, 0x01, 0xdd, 0x03, 0x03, 0x38, 0x02, 0x01, 0xde, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x66, (uint8_t []){0x38, 0x01, 0x01, 0xdf, 0x03, 0x03, 0x38, 0x00, 0x01, 0xe0, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x67, (uint8_t []){0x30, 0x01, 0x01, 0xe1, 0x03, 0x03, 0x30, 0x02, 0x01, 0xe2, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x68, (uint8_t []){0x00, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a}, 13, 0}, +// {0x60, (uint8_t []){0x38, 0x08, 0x7a, 0x7a, 0x38, 0x09, 0x7a, 0x7a}, 8, 0}, +// {0x63, (uint8_t []){0x31, 0xe4, 0x7a, 0x7a, 0x31, 0xe5, 0x7a, 0x7a}, 8, 0}, +// {0x69, (uint8_t []){0x04, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, +// {0x6b, (uint8_t []){0x07}, 1, 0}, +// {0x7a, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0x7b, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0xd1, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd2, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd3, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd4, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd5, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd6, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0x11, (uint8_t []){0x00}, 0, 120}, +// {0x29, (uint8_t []){0x00}, 0, 20}, +// }; +static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { + // {0x11, (uint8_t[]){}, 0, 20}, + + {0xf0, (uint8_t []){0x55, 0xaa, 0x52, 0x08, 0x00}, 5, 0}, + {0xf6, (uint8_t []){0x5a, 0x87}, 2, 0}, + {0xc1, (uint8_t []){0x3f}, 1, 0}, + {0xc2, (uint8_t []){0x0e}, 1, 0}, + {0xc6, (uint8_t []){0xf8}, 1, 0}, + {0xc9, (uint8_t []){0x10}, 1, 0}, + {0xcd, (uint8_t []){0x25}, 1, 0}, + {0xf8, (uint8_t []){0x8a}, 1, 0}, + {0xac, (uint8_t []){0x45}, 1, 0}, + {0xa0, (uint8_t []){0xdd}, 1, 0}, + {0xa7, (uint8_t []){0x47}, 1, 0}, + {0xfa, (uint8_t []){0x00, 0x00, 0x00, 0x04}, 4, 0}, + {0x86, (uint8_t []){0x99, 0xa3, 0xa3, 0x51}, 4, 0}, + {0xa3, (uint8_t []){0xee}, 1, 0}, + {0xfd, (uint8_t []){0x3c, 0x3c, 0x00}, 3, 0}, + {0x71, (uint8_t []){0x48}, 1, 0}, + {0x72, (uint8_t []){0x48}, 1, 0}, + {0x73, (uint8_t []){0x00, 0x44}, 2, 0}, + {0x97, (uint8_t []){0xee}, 1, 0}, + {0x83, (uint8_t []){0x93}, 1, 0}, + {0x9a, (uint8_t []){0x72}, 1, 0}, + {0x9b, (uint8_t []){0x5a}, 1, 0}, + {0x82, (uint8_t []){0x2c, 0x2c}, 2, 0}, + {0x6d, (uint8_t []){0x00, 0x1f, 0x19, 0x1a, 0x10, 0x0e, 0x0c, 0x0a, 0x02, 0x07, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, + 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x08, 0x01, 0x09, 0x0b, 0x0d, 0x0f, 0x1a, 0x19, 0x1f, 0x00}, 32, 0}, + {0x64, (uint8_t []){0x38, 0x05, 0x01, 0xdb, 0x03, 0x03, 0x38, 0x04, 0x01, 0xdc, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x65, (uint8_t []){0x38, 0x03, 0x01, 0xdd, 0x03, 0x03, 0x38, 0x02, 0x01, 0xde, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x66, (uint8_t []){0x38, 0x01, 0x01, 0xdf, 0x03, 0x03, 0x38, 0x00, 0x01, 0xe0, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x67, (uint8_t []){0x30, 0x01, 0x01, 0xe1, 0x03, 0x03, 0x30, 0x02, 0x01, 0xe2, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x68, (uint8_t []){0x00, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a}, 13, 0}, + {0x60, (uint8_t []){0x38, 0x08, 0x7a, 0x7a, 0x38, 0x09, 0x7a, 0x7a}, 8, 0}, + {0x63, (uint8_t []){0x31, 0xe4, 0x7a, 0x7a, 0x31, 0xe5, 0x7a, 0x7a}, 8, 0}, + {0x69, (uint8_t []){0x04, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, + {0x6b, (uint8_t []){0x07}, 1, 0}, + {0x7a, (uint8_t []){0x08, 0x13}, 2, 0}, + {0x7b, (uint8_t []){0x08, 0x13}, 2, 0}, + {0xd1, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd2, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd3, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd4, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd5, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd6, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0x11, (uint8_t []){0x00}, 0, 120}, + {0x29, (uint8_t []){0x00}, 0, 20}, + + }; + +// *INDENT-OFF* + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503) +{ + esp_lcd_panel_io_handle_t io = gc9503->io; + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]){ + gc9503->colmod_val, + }, + 1), + TAG, "send command failed"); + ; + + // Vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + const gc9503_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + if (gc9503->init_cmds) + { + init_cmds = gc9503->init_cmds; + init_cmds_size = gc9503->init_cmds_size; + } + else + { + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(gc9503_lcd_init_cmd_t); + } + + bool is_cmd_overwritten = false; + for (int i = 0; i < init_cmds_size; i++) + { + // Check if the command has been used or conflicts with the internal + switch (init_cmds[i].cmd) + { + case LCD_CMD_MADCTL: + is_cmd_overwritten = true; + gc9503->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + case LCD_CMD_COLMOD: + is_cmd_overwritten = true; + gc9503->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + default: + is_cmd_overwritten = false; + break; + } + + if (is_cmd_overwritten) + { + ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + init_cmds[i].cmd); + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), + TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + } + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (!gc9503->flags.auto_del_panel_io) + { + ESP_RETURN_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), TAG, "send init commands failed"); + } + // Init RGB panel + ESP_RETURN_ON_ERROR(gc9503->init(panel), TAG, "init RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (gc9503->reset_gpio_num >= 0) + { + gpio_reset_pin(gc9503->reset_gpio_num); + } + // Delete RGB panel + gc9503->del(panel); + free(gc9503); + ESP_LOGD(TAG, "del gc9503 panel @%p", gc9503); + return ESP_OK; +} + +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + // Perform hardware reset + if (gc9503->reset_gpio_num >= 0) + { + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(120)); + } + else if (io) + { // Perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(120)); + } + // Reset RGB panel + ESP_RETURN_ON_ERROR(gc9503->reset(panel), TAG, "reset RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + if (gc9503->flags.mirror_by_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control mirror through LCD command + if (mirror_x) + { + gc9503->madctl_val |= GC9503_CMD_GS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_GS_BIT; + } + if (mirror_y) + { + gc9503->madctl_val |= GC9503_CMD_SS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_SS_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + } + else + { + // Control mirror through RGB panel + ESP_RETURN_ON_ERROR(gc9503->mirror(panel, mirror_x, mirror_y), TAG, "RGB panel mirror failed"); + } + return ESP_OK; +} + +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + int command = 0; + + if (gc9503->flags.display_on_off_use_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control display on/off through LCD command + if (on_off) + { + command = LCD_CMD_DISPON; + } + else + { + command = LCD_CMD_DISPOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + } + else + { + // Control display on/off through display control signal + ESP_RETURN_ON_ERROR(gc9503->disp_on_off(panel, on_off), TAG, "RGB panel disp_on_off failed"); + } + return ESP_OK; +} diff --git a/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.h b/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.h new file mode 100644 index 0000000..4d926d9 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board-2/esp_lcd_gc9503.h @@ -0,0 +1,146 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * @file + * @brief ESP LCD: GC9503 + */ + +#pragma once + +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct { + int cmd; /* IO48 +I2C_SDA IO8 -> IO47 +LCD_DATA6 IO47 -> IO8 +LCD_DATA7 IO48 -> IO18 + + +本版本只支持了480x480的屏幕 \ No newline at end of file diff --git a/main/boards/esp-s3-lcd-ev-board/config.h b/main/boards/esp-s3-lcd-ev-board/config.h new file mode 100644 index 0000000..4db1775 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/config.h @@ -0,0 +1,53 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_7 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_6 + +#define BSP_POWER_AMP_IO (IO_EXPANDER_PIN_NUM_0) +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC + +//如果开发板是V1.4 IO 定义为 +#ifdef CONFIG_ESP_S3_LCD_EV_Board_1p4 + #define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 + #define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_18 +#endif +//如果开发板是V1.5 IO 定义为 +#ifdef CONFIG_ESP_S3_LCD_EV_Board_1p5 + #define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 + #define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#endif + +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR 0x82 + + +#define BUILTIN_LED_GPIO GPIO_NUM_4 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_WIDTH 480 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_19 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + + + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-s3-lcd-ev-board/config.json b/main/boards/esp-s3-lcd-ev-board/config.json new file mode 100644 index 0000000..55d1602 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/config.json @@ -0,0 +1,17 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-s3-lcd-ev-board-1p4", + "sdkconfig_append": [ + "CONFIG_ESP_S3_LCD_EV_Board_1p4=y" + ] + }, + { + "name": "esp-s3-lcd-ev-board-1p5", + "sdkconfig_append": [ + "CONFIG_ESP_S3_LCD_EV_Board_1p5=y" + ] + } + ] +} diff --git a/main/boards/esp-s3-lcd-ev-board/esp-s3-lcd-ev-board.cc b/main/boards/esp-s3-lcd-ev-board/esp-s3-lcd-ev-board.cc new file mode 100644 index 0000000..990a3e3 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/esp-s3-lcd-ev-board.cc @@ -0,0 +1,204 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "pin_config.h" + +#include "config.h" + +#include +#include +#include +#include "esp_lcd_gc9503.h" +#include +#include +#include + +#include "esp_io_expander_tca9554.h" + +#define TAG "ESP_S3_LCD_EV_Board" + +class ESP_S3_LCD_EV_Board : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + //add support ev board lcd + esp_io_expander_handle_t expander = NULL; + + void InitializeRGB_GC9503V_Display() { + ESP_LOGI(TAG, "Init GC9503V"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + + //add support ev board lcd + gpio_config_t io_conf = { + .pin_bit_mask = BIT64(GC9503V_PIN_NUM_VSYNC), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_ENABLE, + }; + + gpio_config(&io_conf); + gpio_set_level(GC9503V_PIN_NUM_VSYNC, 1); + + ESP_LOGI(TAG, "Install 3-wire SPI panel IO"); + spi_line_config_t line_config = { + .cs_io_type = IO_TYPE_EXPANDER, + .cs_expander_pin = GC9503V_LCD_IO_SPI_CS_1, + .scl_io_type = IO_TYPE_EXPANDER, + .scl_expander_pin = GC9503V_LCD_IO_SPI_SCL_1, + .sda_io_type = IO_TYPE_EXPANDER, + .sda_expander_pin = GC9503V_LCD_IO_SPI_SDO_1, + .io_expander = expander, + }; + + esp_lcd_panel_io_3wire_spi_config_t io_config = GC9503_PANEL_IO_3WIRE_SPI_CONFIG(line_config, 0); + int espok = esp_lcd_new_panel_io_3wire_spi(&io_config, &panel_io); + ESP_LOGI(TAG, "Install 3-wire SPI panel IO:%d",espok); + + ESP_LOGI(TAG, "Install RGB LCD panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_rgb_panel_config_t rgb_config = { + .clk_src = LCD_CLK_SRC_PLL160M, + //.timings = GC9503_376_960_PANEL_60HZ_RGB_TIMING(), + //add support ev board + .timings = GC9503_480_480_PANEL_60HZ_RGB_TIMING(), + .data_width = 16, // RGB565 in parallel mode, thus 16bit in width + .bits_per_pixel = 16, + .num_fbs = GC9503V_LCD_RGB_BUFFER_NUMS, + .bounce_buffer_size_px = GC9503V_LCD_H_RES * GC9503V_LCD_RGB_BOUNCE_BUFFER_HEIGHT, + .dma_burst_size = 64, + .hsync_gpio_num = GC9503V_PIN_NUM_HSYNC, + .vsync_gpio_num = GC9503V_PIN_NUM_VSYNC, + .de_gpio_num = GC9503V_PIN_NUM_DE, + .pclk_gpio_num = GC9503V_PIN_NUM_PCLK, + .disp_gpio_num = GC9503V_PIN_NUM_DISP_EN, + .data_gpio_nums = { + GC9503V_PIN_NUM_DATA0, + GC9503V_PIN_NUM_DATA1, + GC9503V_PIN_NUM_DATA2, + GC9503V_PIN_NUM_DATA3, + GC9503V_PIN_NUM_DATA4, + GC9503V_PIN_NUM_DATA5, + GC9503V_PIN_NUM_DATA6, + GC9503V_PIN_NUM_DATA7, + GC9503V_PIN_NUM_DATA8, + GC9503V_PIN_NUM_DATA9, + GC9503V_PIN_NUM_DATA10, + GC9503V_PIN_NUM_DATA11, + GC9503V_PIN_NUM_DATA12, + GC9503V_PIN_NUM_DATA13, + GC9503V_PIN_NUM_DATA14, + GC9503V_PIN_NUM_DATA15, + }, + .flags= { + .fb_in_psram = true, // allocate frame buffer in PSRAM + } + }; + + ESP_LOGI(TAG, "Initialize RGB LCD panel"); + + gc9503_vendor_config_t vendor_config = { + .rgb_config = &rgb_config, + .flags = { + .mirror_by_cmd = 0, + .auto_del_panel_io = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = -1, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + // .bits_per_pixel = 16, + //add surpport ev board + .bits_per_pixel = 18, + .vendor_config = &vendor_config, + }; + (esp_lcd_new_panel_gc9503(panel_io, &panel_config, &panel_handle)); + (esp_lcd_panel_reset(panel_handle)); + (esp_lcd_panel_init(panel_handle)); + + display_ = new RgbLcdDisplay(panel_io, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + //add support ev board lcd amp + //初始化扩展io口 + esp_io_expander_new_i2c_tca9554(codec_i2c_bus_, 0x20, &expander); + /* Setup power amplifier pin, set default to enable */ + esp_io_expander_set_dir(expander, BSP_POWER_AMP_IO, IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(expander, BSP_POWER_AMP_IO, true); + + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + +public: + ESP_S3_LCD_EV_Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializeRGB_GC9503V_Display(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + codec_i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + true); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + //添加彩灯显示状态,如果亮度太暗可以去更改默认亮度值 DEFAULT_BRIGHTNESS 在led的sigle_led.cc中 + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + +}; + +DECLARE_BOARD(ESP_S3_LCD_EV_Board); diff --git a/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.c b/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.c new file mode 100644 index 0000000..321472f --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.c @@ -0,0 +1,154 @@ +/* + * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include "esp_bit_defs.h" +#include "esp_check.h" +#include "esp_log.h" +#include "esp_io_expander.h" +#include "esp_io_expander_tca9554.h" + +/* I2C communication related */ +#define I2C_TIMEOUT_MS (1000) +#define I2C_CLK_SPEED (400000) + +#define IO_COUNT (8) + +/* Register address */ +#define INPUT_REG_ADDR (0x00) +#define OUTPUT_REG_ADDR (0x01) +#define DIRECTION_REG_ADDR (0x03) + +/* Default register value on power-up */ +#define DIR_REG_DEFAULT_VAL (0xff) +#define OUT_REG_DEFAULT_VAL (0xff) + +/** + * @brief Device Structure Type + * + */ +typedef struct { + esp_io_expander_t base; + i2c_master_dev_handle_t i2c_handle; + struct { + uint8_t direction; + uint8_t output; + } regs; +} esp_io_expander_tca9554_t; + +static char *TAG = "tca9554"; + +static esp_err_t read_input_reg(esp_io_expander_handle_t handle, uint32_t *value); +static esp_err_t write_output_reg(esp_io_expander_handle_t handle, uint32_t value); +static esp_err_t read_output_reg(esp_io_expander_handle_t handle, uint32_t *value); +static esp_err_t write_direction_reg(esp_io_expander_handle_t handle, uint32_t value); +static esp_err_t read_direction_reg(esp_io_expander_handle_t handle, uint32_t *value); +static esp_err_t reset(esp_io_expander_t *handle); +static esp_err_t del(esp_io_expander_t *handle); + +esp_err_t esp_io_expander_new_i2c_tca9554(i2c_master_bus_handle_t i2c_bus, uint32_t dev_addr, esp_io_expander_handle_t *handle_ret) +{ + ESP_RETURN_ON_FALSE(handle_ret != NULL, ESP_ERR_INVALID_ARG, TAG, "Invalid handle_ret"); + + // Allocate memory for driver object + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)calloc(1, sizeof(esp_io_expander_tca9554_t)); + ESP_RETURN_ON_FALSE(tca9554 != NULL, ESP_ERR_NO_MEM, TAG, "Malloc failed"); + + // Add new I2C device + esp_err_t ret = ESP_OK; + const i2c_device_config_t i2c_dev_cfg = { + .device_address = dev_addr, + .scl_speed_hz = I2C_CLK_SPEED, + }; + ESP_GOTO_ON_ERROR(i2c_master_bus_add_device(i2c_bus, &i2c_dev_cfg, &tca9554->i2c_handle), err, TAG, "Add new I2C device failed"); + + tca9554->base.config.io_count = IO_COUNT; + tca9554->base.config.flags.dir_out_bit_zero = 1; + tca9554->base.read_input_reg = read_input_reg; + tca9554->base.write_output_reg = write_output_reg; + tca9554->base.read_output_reg = read_output_reg; + tca9554->base.write_direction_reg = write_direction_reg; + tca9554->base.read_direction_reg = read_direction_reg; + tca9554->base.del = del; + tca9554->base.reset = reset; + + /* Reset configuration and register status */ + ESP_GOTO_ON_ERROR(reset(&tca9554->base), err, TAG, "Reset failed"); + + *handle_ret = &tca9554->base; + return ESP_OK; +err: + free(tca9554); + return ret; +} + +static esp_err_t read_input_reg(esp_io_expander_handle_t handle, uint32_t *value) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + + uint8_t temp = 0; + ESP_RETURN_ON_ERROR(i2c_master_transmit_receive(tca9554->i2c_handle, (uint8_t[]) { + INPUT_REG_ADDR + }, 1, &temp, sizeof(temp), I2C_TIMEOUT_MS), TAG, "Read input reg failed"); + *value = temp; + return ESP_OK; +} + +static esp_err_t write_output_reg(esp_io_expander_handle_t handle, uint32_t value) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + value &= 0xff; + + uint8_t data[] = {OUTPUT_REG_ADDR, value}; + ESP_RETURN_ON_ERROR(i2c_master_transmit(tca9554->i2c_handle, data, sizeof(data), I2C_TIMEOUT_MS), TAG, "Write output reg failed"); + tca9554->regs.output = value; + return ESP_OK; +} + +static esp_err_t read_output_reg(esp_io_expander_handle_t handle, uint32_t *value) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + + *value = tca9554->regs.output; + return ESP_OK; +} + +static esp_err_t write_direction_reg(esp_io_expander_handle_t handle, uint32_t value) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + value &= 0xff; + + uint8_t data[] = {DIRECTION_REG_ADDR, value}; + ESP_RETURN_ON_ERROR(i2c_master_transmit(tca9554->i2c_handle, data, sizeof(data), I2C_TIMEOUT_MS), TAG, "Write direction reg failed"); + tca9554->regs.direction = value; + return ESP_OK; +} + +static esp_err_t read_direction_reg(esp_io_expander_handle_t handle, uint32_t *value) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + + *value = tca9554->regs.direction; + return ESP_OK; +} + +static esp_err_t reset(esp_io_expander_t *handle) +{ + ESP_RETURN_ON_ERROR(write_direction_reg(handle, DIR_REG_DEFAULT_VAL), TAG, "Write dir reg failed"); + ESP_RETURN_ON_ERROR(write_output_reg(handle, OUT_REG_DEFAULT_VAL), TAG, "Write output reg failed"); + return ESP_OK; +} + +static esp_err_t del(esp_io_expander_t *handle) +{ + esp_io_expander_tca9554_t *tca9554 = (esp_io_expander_tca9554_t *)__containerof(handle, esp_io_expander_tca9554_t, base); + + ESP_RETURN_ON_ERROR(i2c_master_bus_rm_device(tca9554->i2c_handle), TAG, "Remove I2C device failed"); + free(tca9554); + return ESP_OK; +} diff --git a/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.h b/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.h new file mode 100644 index 0000000..192107c --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/esp_io_expander_tca9554.h @@ -0,0 +1,90 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @file + * @brief ESP IO expander: TCA9554 + */ + +#pragma once + +#include +#include "esp_err.h" +#include "driver/i2c_master.h" +#include "esp_io_expander.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Create a TCA9554(A) IO expander object + * + * @param[in] i2c_bus I2C bus handle. Obtained from `i2c_new_master_bus()` + * @param[in] dev_addr I2C device address of chip. Can be `ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_XXX` or `ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_XXX`. + * @param[out] handle_ret Handle to created IO expander object + * + * @return + * - ESP_OK: Success, otherwise returns ESP_ERR_xxx + */ +esp_err_t esp_io_expander_new_i2c_tca9554(i2c_master_bus_handle_t i2c_bus, uint32_t dev_addr, esp_io_expander_handle_t *handle_ret); + +/** + * @brief I2C address of the TCA9554 + * + * The 8-bit address format is as follows: + * + * (Slave Address) + * ┌─────────────────┷─────────────────┐ + * ┌─────┐─────┐─────┐─────┐─────┐─────┐─────┐─────┐ + * | 0 | 1 | 0 | 0 | A2 | A1 | A0 | R/W | + * └─────┘─────┘─────┘─────┘─────┘─────┘─────┘─────┘ + * └────────┯────────┘ └─────┯──────┘ + * (Fixed) (Hareware Selectable) + * + * And the 7-bit slave address is the most important data for users. + * For example, if a chip's A0,A1,A2 are connected to GND, it's 7-bit slave address is 0100000b(0x20). + * Then users can use `ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000` to init it. + */ +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 (0x20) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_001 (0x21) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_010 (0x22) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_011 (0x23) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_100 (0x24) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_101 (0x25) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_110 (0x26) +#define ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_111 (0x27) + + +/** + * @brief I2C address of the TCA9554A + * + * The 8-bit address format is as follows: + * + * (Slave Address) + * ┌─────────────────┷─────────────────┐ + * ┌─────┐─────┐─────┐─────┐─────┐─────┐─────┐─────┐ + * | 0 | 1 | 1 | 1 | A2 | A1 | A0 | R/W | + * └─────┘─────┘─────┘─────┘─────┘─────┘─────┘─────┘ + * └────────┯────────┘ └─────┯──────┘ + * (Fixed) (Hareware Selectable) + * + * And the 7-bit slave address is the most important data for users. + * For example, if a chip's A0,A1,A2 are connected to GND, it's 7-bit slave address is 0111000b(0x38). + * Then users can use `ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_000` to init it. + */ +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_000 (0x38) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_001 (0x39) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_010 (0x3A) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_011 (0x3B) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_100 (0x3C) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_101 (0x3D) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_110 (0x3E) +#define ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_111 (0x3F) + +#ifdef __cplusplus +} +#endif diff --git a/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.c b/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.c new file mode 100644 index 0000000..4db550e --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.c @@ -0,0 +1,504 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "esp_lcd_gc9503.h" + +#define GC9503_CMD_MADCTL (0xB1) // Memory data access control +#define GC9503_CMD_MADCTL_DEFAULT (0x10) // Default value of Memory data access control +#define GC9503_CMD_SS_BIT (1 << 0) // Source driver scan direction, 0: top to bottom, 1: bottom to top +#define GC9503_CMD_GS_BIT (1 << 1) // Gate driver scan direction, 0: left to right, 1: right to left +#define GC9503_CMD_BGR_BIT (1 << 5) // RGB/BGR order, 0: RGB, 1: BGR + +typedef struct +{ + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // Save current value of GC9503_CMD_MADCTL register + uint8_t colmod_val; // Save current value of LCD_CMD_COLMOD register + const gc9503_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + struct + { + unsigned int mirror_by_cmd : 1; + unsigned int auto_del_panel_io : 1; + unsigned int display_on_off_use_cmd : 1; + unsigned int reset_level : 1; + } flags; + // To save the original functions of RGB panel + esp_err_t (*init)(esp_lcd_panel_t *panel); + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*reset)(esp_lcd_panel_t *panel); + esp_err_t (*mirror)(esp_lcd_panel_t *panel, bool x_axis, bool y_axis); + esp_err_t (*disp_on_off)(esp_lcd_panel_t *panel, bool on_off); +} gc9503_panel_t; + +static const char *TAG = "gc9503"; + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503); + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool off); + +esp_err_t esp_lcd_new_panel_gc9503(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + gc9503_vendor_config_t *vendor_config = (gc9503_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->rgb_config, ESP_ERR_INVALID_ARG, TAG, "`verndor_config` and `rgb_config` are necessary"); + ESP_RETURN_ON_FALSE(!vendor_config->flags.auto_del_panel_io || !vendor_config->flags.mirror_by_cmd, + ESP_ERR_INVALID_ARG, TAG, "`mirror_by_cmd` and `auto_del_panel_io` cannot work together"); + + esp_err_t ret = ESP_OK; + gpio_config_t io_conf = {0}; + + gc9503_panel_t *gc9503 = (gc9503_panel_t *)calloc(1, sizeof(gc9503_panel_t)); + ESP_RETURN_ON_FALSE(gc9503, ESP_ERR_NO_MEM, TAG, "no mem for gc9503 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + gc9503->madctl_val = GC9503_CMD_MADCTL_DEFAULT; + switch (panel_dev_config->rgb_ele_order) + { + case LCD_RGB_ELEMENT_ORDER_RGB: + gc9503->madctl_val &= ~GC9503_CMD_BGR_BIT; + break; + case LCD_RGB_ELEMENT_ORDER_BGR: + gc9503->madctl_val |= GC9503_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color element order"); + break; + } + + gc9503->colmod_val = 0; + switch (panel_dev_config->bits_per_pixel) + { + case 16: // RGB565 + gc9503->colmod_val = 0x50; + break; + case 18: // RGB666 + gc9503->colmod_val = 0x60; + break; + case 24: // RGB888 + gc9503->colmod_val = 0x70; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + gc9503->io = io; + gc9503->init_cmds = vendor_config->init_cmds; + gc9503->init_cmds_size = vendor_config->init_cmds_size; + gc9503->reset_gpio_num = panel_dev_config->reset_gpio_num; + gc9503->flags.reset_level = panel_dev_config->flags.reset_active_high; + gc9503->flags.auto_del_panel_io = vendor_config->flags.auto_del_panel_io; + gc9503->flags.mirror_by_cmd = vendor_config->flags.mirror_by_cmd; + gc9503->flags.display_on_off_use_cmd = (vendor_config->rgb_config->disp_gpio_num >= 0) ? 0 : 1; + + if (gc9503->flags.auto_del_panel_io) + { + if (gc9503->reset_gpio_num >= 0) + { // Perform hardware reset + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + } + else + { // Perform software reset + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), err, TAG, "send command failed"); + } + vTaskDelay(pdMS_TO_TICKS(120)); + + /** + * In order to enable the 3-wire SPI interface pins (such as SDA and SCK) to share other pins of the RGB interface + * (such as HSYNC) and save GPIOs, we need to send LCD initialization commands via the 3-wire SPI interface before + * `esp_lcd_new_rgb_panel()` is called. + */ + ESP_GOTO_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), err, TAG, "send init commands failed"); + // After sending the initialization commands, the 3-wire SPI interface can be deleted + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_del(io), err, TAG, "delete panel IO failed"); + gc9503->io = NULL; + ESP_LOGD(TAG, "delete panel IO"); + } + + // Create RGB panel + ESP_GOTO_ON_ERROR(esp_lcd_new_rgb_panel(vendor_config->rgb_config, ret_panel), err, TAG, "create RGB panel failed"); + ESP_LOGD(TAG, "new RGB panel @%p", ret_panel); + + // Save the original functions of RGB panel + gc9503->init = (*ret_panel)->init; + gc9503->del = (*ret_panel)->del; + gc9503->reset = (*ret_panel)->reset; + gc9503->mirror = (*ret_panel)->mirror; + gc9503->disp_on_off = (*ret_panel)->disp_on_off; + // Overwrite the functions of RGB panel + (*ret_panel)->init = panel_gc9503_init; + (*ret_panel)->del = panel_gc9503_del; + (*ret_panel)->reset = panel_gc9503_reset; + (*ret_panel)->mirror = panel_gc9503_mirror; + (*ret_panel)->disp_on_off = panel_gc9503_disp_on_off; + (*ret_panel)->user_data = gc9503; + ESP_LOGD(TAG, "new gc9503 panel @%p", gc9503); + + // ESP_LOGI(TAG, "LCD panel create success, version: %d.%d.%d", ESP_LCD_GC9503_VER_MAJOR, ESP_LCD_GC9503_VER_MINOR, + // ESP_LCD_GC9503_VER_PATCH); + return ESP_OK; + +err: + if (gc9503) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(gc9503); + } + return ret; +} + +// *INDENT-OFF* +// static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { +// // {cmd, { data }, data_size, delay_ms} +// {0x11, (uint8_t []){0x00}, 0, 120}, + +// {0xf0, (uint8_t []){0x55, 0xaa, 0x52, 0x08, 0x00}, 5, 0}, +// {0xf6, (uint8_t []){0x5a, 0x87}, 2, 0}, +// {0xc1, (uint8_t []){0x3f}, 1, 0}, +// {0xc2, (uint8_t []){0x0e}, 1, 0}, +// {0xc6, (uint8_t []){0xf8}, 1, 0}, +// {0xc9, (uint8_t []){0x10}, 1, 0}, +// {0xcd, (uint8_t []){0x25}, 1, 0}, +// {0xf8, (uint8_t []){0x8a}, 1, 0}, +// {0xac, (uint8_t []){0x45}, 1, 0}, +// {0xa0, (uint8_t []){0xdd}, 1, 0}, +// {0xa7, (uint8_t []){0x47}, 1, 0}, +// {0xfa, (uint8_t []){0x00, 0x00, 0x00, 0x04}, 4, 0}, +// {0x86, (uint8_t []){0x99, 0xa3, 0xa3, 0x51}, 4, 0}, +// {0xa3, (uint8_t []){0xee}, 1, 0}, +// {0xfd, (uint8_t []){0x3c, 0x3c, 0x00}, 3, 0}, +// {0x71, (uint8_t []){0x48}, 1, 0}, +// {0x72, (uint8_t []){0x48}, 1, 0}, +// {0x73, (uint8_t []){0x00, 0x44}, 2, 0}, +// {0x97, (uint8_t []){0xee}, 1, 0}, +// {0x83, (uint8_t []){0x93}, 1, 0}, +// {0x9a, (uint8_t []){0x72}, 1, 0}, +// {0x9b, (uint8_t []){0x5a}, 1, 0}, +// {0x82, (uint8_t []){0x2c, 0x2c}, 2, 0}, +// {0x6d, (uint8_t []){0x00, 0x1f, 0x19, 0x1a, 0x10, 0x0e, 0x0c, 0x0a, 0x02, 0x07, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, +// 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x08, 0x01, 0x09, 0x0b, 0x0d, 0x0f, 0x1a, 0x19, 0x1f, 0x00}, 32, 0}, +// {0x64, (uint8_t []){0x38, 0x05, 0x01, 0xdb, 0x03, 0x03, 0x38, 0x04, 0x01, 0xdc, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x65, (uint8_t []){0x38, 0x03, 0x01, 0xdd, 0x03, 0x03, 0x38, 0x02, 0x01, 0xde, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x66, (uint8_t []){0x38, 0x01, 0x01, 0xdf, 0x03, 0x03, 0x38, 0x00, 0x01, 0xe0, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x67, (uint8_t []){0x30, 0x01, 0x01, 0xe1, 0x03, 0x03, 0x30, 0x02, 0x01, 0xe2, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x68, (uint8_t []){0x00, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a}, 13, 0}, +// {0x60, (uint8_t []){0x38, 0x08, 0x7a, 0x7a, 0x38, 0x09, 0x7a, 0x7a}, 8, 0}, +// {0x63, (uint8_t []){0x31, 0xe4, 0x7a, 0x7a, 0x31, 0xe5, 0x7a, 0x7a}, 8, 0}, +// {0x69, (uint8_t []){0x04, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, +// {0x6b, (uint8_t []){0x07}, 1, 0}, +// {0x7a, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0x7b, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0xd1, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd2, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd3, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd4, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd5, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd6, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0x11, (uint8_t []){0x00}, 0, 120}, +// {0x29, (uint8_t []){0x00}, 0, 20}, +// }; +static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { + // {0x11, (uint8_t[]){}, 0, 20}, + + {0xf0, (uint8_t []){0x55, 0xaa, 0x52, 0x08, 0x00}, 5, 0}, + {0xf6, (uint8_t []){0x5a, 0x87}, 2, 0}, + {0xc1, (uint8_t []){0x3f}, 1, 0}, + {0xc2, (uint8_t []){0x0e}, 1, 0}, + {0xc6, (uint8_t []){0xf8}, 1, 0}, + {0xc9, (uint8_t []){0x10}, 1, 0}, + {0xcd, (uint8_t []){0x25}, 1, 0}, + {0xf8, (uint8_t []){0x8a}, 1, 0}, + {0xac, (uint8_t []){0x45}, 1, 0}, + {0xa0, (uint8_t []){0xdd}, 1, 0}, + {0xa7, (uint8_t []){0x47}, 1, 0}, + {0xfa, (uint8_t []){0x00, 0x00, 0x00, 0x04}, 4, 0}, + {0x86, (uint8_t []){0x99, 0xa3, 0xa3, 0x51}, 4, 0}, + {0xa3, (uint8_t []){0xee}, 1, 0}, + {0xfd, (uint8_t []){0x3c, 0x3c, 0x00}, 3, 0}, + {0x71, (uint8_t []){0x48}, 1, 0}, + {0x72, (uint8_t []){0x48}, 1, 0}, + {0x73, (uint8_t []){0x00, 0x44}, 2, 0}, + {0x97, (uint8_t []){0xee}, 1, 0}, + {0x83, (uint8_t []){0x93}, 1, 0}, + {0x9a, (uint8_t []){0x72}, 1, 0}, + {0x9b, (uint8_t []){0x5a}, 1, 0}, + {0x82, (uint8_t []){0x2c, 0x2c}, 2, 0}, + {0x6d, (uint8_t []){0x00, 0x1f, 0x19, 0x1a, 0x10, 0x0e, 0x0c, 0x0a, 0x02, 0x07, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, + 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x08, 0x01, 0x09, 0x0b, 0x0d, 0x0f, 0x1a, 0x19, 0x1f, 0x00}, 32, 0}, + {0x64, (uint8_t []){0x38, 0x05, 0x01, 0xdb, 0x03, 0x03, 0x38, 0x04, 0x01, 0xdc, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x65, (uint8_t []){0x38, 0x03, 0x01, 0xdd, 0x03, 0x03, 0x38, 0x02, 0x01, 0xde, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x66, (uint8_t []){0x38, 0x01, 0x01, 0xdf, 0x03, 0x03, 0x38, 0x00, 0x01, 0xe0, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x67, (uint8_t []){0x30, 0x01, 0x01, 0xe1, 0x03, 0x03, 0x30, 0x02, 0x01, 0xe2, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, + {0x68, (uint8_t []){0x00, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a}, 13, 0}, + {0x60, (uint8_t []){0x38, 0x08, 0x7a, 0x7a, 0x38, 0x09, 0x7a, 0x7a}, 8, 0}, + {0x63, (uint8_t []){0x31, 0xe4, 0x7a, 0x7a, 0x31, 0xe5, 0x7a, 0x7a}, 8, 0}, + {0x69, (uint8_t []){0x04, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, + {0x6b, (uint8_t []){0x07}, 1, 0}, + {0x7a, (uint8_t []){0x08, 0x13}, 2, 0}, + {0x7b, (uint8_t []){0x08, 0x13}, 2, 0}, + {0xd1, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd2, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd3, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd4, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd5, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0xd6, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, + 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, + 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, + 0xff}, 52, 0}, + {0x11, (uint8_t []){0x00}, 0, 120}, + {0x29, (uint8_t []){0x00}, 0, 20}, + + }; + +// *INDENT-OFF* + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503) +{ + esp_lcd_panel_io_handle_t io = gc9503->io; + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]){ + gc9503->colmod_val, + }, + 1), + TAG, "send command failed"); + ; + + // Vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + const gc9503_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + if (gc9503->init_cmds) + { + init_cmds = gc9503->init_cmds; + init_cmds_size = gc9503->init_cmds_size; + } + else + { + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(gc9503_lcd_init_cmd_t); + } + + bool is_cmd_overwritten = false; + for (int i = 0; i < init_cmds_size; i++) + { + // Check if the command has been used or conflicts with the internal + switch (init_cmds[i].cmd) + { + case LCD_CMD_MADCTL: + is_cmd_overwritten = true; + gc9503->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + case LCD_CMD_COLMOD: + is_cmd_overwritten = true; + gc9503->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + default: + is_cmd_overwritten = false; + break; + } + + if (is_cmd_overwritten) + { + ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + init_cmds[i].cmd); + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), + TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + } + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (!gc9503->flags.auto_del_panel_io) + { + ESP_RETURN_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), TAG, "send init commands failed"); + } + // Init RGB panel + ESP_RETURN_ON_ERROR(gc9503->init(panel), TAG, "init RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (gc9503->reset_gpio_num >= 0) + { + gpio_reset_pin(gc9503->reset_gpio_num); + } + // Delete RGB panel + gc9503->del(panel); + free(gc9503); + ESP_LOGD(TAG, "del gc9503 panel @%p", gc9503); + return ESP_OK; +} + +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + // Perform hardware reset + if (gc9503->reset_gpio_num >= 0) + { + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(120)); + } + else if (io) + { // Perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(120)); + } + // Reset RGB panel + ESP_RETURN_ON_ERROR(gc9503->reset(panel), TAG, "reset RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + if (gc9503->flags.mirror_by_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control mirror through LCD command + if (mirror_x) + { + gc9503->madctl_val |= GC9503_CMD_GS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_GS_BIT; + } + if (mirror_y) + { + gc9503->madctl_val |= GC9503_CMD_SS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_SS_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + } + else + { + // Control mirror through RGB panel + ESP_RETURN_ON_ERROR(gc9503->mirror(panel, mirror_x, mirror_y), TAG, "RGB panel mirror failed"); + } + return ESP_OK; +} + +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + int command = 0; + + if (gc9503->flags.display_on_off_use_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control display on/off through LCD command + if (on_off) + { + command = LCD_CMD_DISPON; + } + else + { + command = LCD_CMD_DISPOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + } + else + { + // Control display on/off through display control signal + ESP_RETURN_ON_ERROR(gc9503->disp_on_off(panel, on_off), TAG, "RGB panel disp_on_off failed"); + } + return ESP_OK; +} diff --git a/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.h b/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.h new file mode 100644 index 0000000..8feafd1 --- /dev/null +++ b/main/boards/esp-s3-lcd-ev-board/esp_lcd_gc9503.h @@ -0,0 +1,167 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * @file + * @brief ESP LCD: GC9503 + */ + +#pragma once + +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct { + int cmd; /* +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_45 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_41 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_42 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_4 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_5 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_DC_GPIO GPIO_NUM_43 +#define DISPLAY_CS_GPIO GPIO_NUM_44 +#define DISPLAY_CLK_GPIO GPIO_NUM_21 +#define DISPLAY_MOSI_GPIO GPIO_NUM_47 +#define DISPLAY_RST_GPIO GPIO_NUM_NC + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_46 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define UART_ECHO_TXD GPIO_NUM_38 +#define UART_ECHO_RXD GPIO_NUM_48 +#define UART_ECHO_RTS (-1) +#define UART_ECHO_CTS (-1) + +#define MOTOR_SPEED_MAX 100 +#define MOTOR_SPEED_80 80 +#define MOTOR_SPEED_60 60 +#define MOTOR_SPEED_MIN 0 + +#define ECHO_UART_PORT_NUM UART_NUM_1 +#define ECHO_UART_BAUD_RATE (115200) +#define BUF_SIZE (1024) + +typedef enum { + LIGHT_MODE_CHARGING_BREATH = 0, + LIGHT_MODE_POWER_LOW, + LIGHT_MODE_ALWAYS_ON, + LIGHT_MODE_BLINK, + LIGHT_MODE_WHITE_BREATH_SLOW, + LIGHT_MODE_WHITE_BREATH_FAST, + LIGHT_MODE_FLOWING, + LIGHT_MODE_SHOW, + LIGHT_MODE_SLEEP, + LIGHT_MODE_MAX +} light_mode_t; + +/* Camera PINs*/ +#define SPARKBOT_CAMERA_XCLK (GPIO_NUM_15) +#define SPARKBOT_CAMERA_PCLK (GPIO_NUM_13) +#define SPARKBOT_CAMERA_VSYNC (GPIO_NUM_6) +#define SPARKBOT_CAMERA_HSYNC (GPIO_NUM_7) +#define SPARKBOT_CAMERA_D0 (GPIO_NUM_11) +#define SPARKBOT_CAMERA_D1 (GPIO_NUM_9) +#define SPARKBOT_CAMERA_D2 (GPIO_NUM_8) +#define SPARKBOT_CAMERA_D3 (GPIO_NUM_10) +#define SPARKBOT_CAMERA_D4 (GPIO_NUM_12) +#define SPARKBOT_CAMERA_D5 (GPIO_NUM_18) +#define SPARKBOT_CAMERA_D6 (GPIO_NUM_17) +#define SPARKBOT_CAMERA_D7 (GPIO_NUM_16) + +#define SPARKBOT_CAMERA_PWDN (GPIO_NUM_NC) +#define SPARKBOT_CAMERA_RESET (GPIO_NUM_NC) +#define SPARKBOT_CAMERA_XCLK (GPIO_NUM_15) +#define SPARKBOT_CAMERA_PCLK (GPIO_NUM_13) +#define SPARKBOT_CAMERA_VSYNC (GPIO_NUM_6) +#define SPARKBOT_CAMERA_HSYNC (GPIO_NUM_7) + +#define SPARKBOT_CAMERA_XCLK_FREQ (16000000) +#define SPARKBOT_LEDC_TIMER (LEDC_TIMER_0) +#define SPARKBOT_LEDC_CHANNEL (LEDC_CHANNEL_0) + +#define SPARKBOT_CAMERA_SIOD (GPIO_NUM_NC) +#define SPARKBOT_CAMERA_SIOC (GPIO_NUM_NC) + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp-sparkbot/config.json b/main/boards/esp-sparkbot/config.json new file mode 100644 index 0000000..0cebab5 --- /dev/null +++ b/main/boards/esp-sparkbot/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp-sparkbot", + "sdkconfig_append": [ + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_240X240_25FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp-sparkbot/esp_sparkbot_board.cc b/main/boards/esp-sparkbot/esp_sparkbot_board.cc new file mode 100644 index 0000000..e55f84e --- /dev/null +++ b/main/boards/esp-sparkbot/esp_sparkbot_board.cc @@ -0,0 +1,302 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "settings.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "esp32_camera.h" + +#define TAG "esp_sparkbot" + +class SparkBotEs8311AudioCodec : public Es8311AudioCodec { +private: + +public: + SparkBotEs8311AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, bool use_mclk = true) + : Es8311AudioCodec(i2c_master_handle, i2c_port, input_sample_rate, output_sample_rate, + mclk, bclk, ws, dout, din,pa_pin, es8311_addr, use_mclk = true) {} + + void EnableOutput(bool enable) override { + if (enable == output_enabled_) { + return; + } + if (enable) { + Es8311AudioCodec::EnableOutput(enable); + } else { + // Nothing todo because the display io and PA io conflict + } + } +}; + +class EspSparkBot : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Display* display_; + Esp32Camera* camera_; + light_mode_t light_mode_ = LIGHT_MODE_ALWAYS_ON; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_GPIO; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_GPIO; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_GPIO; + io_config.dc_gpio_num = DISPLAY_DC_GPIO; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + + // DVP pin configuration + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = SPARKBOT_CAMERA_D0, + [1] = SPARKBOT_CAMERA_D1, + [2] = SPARKBOT_CAMERA_D2, + [3] = SPARKBOT_CAMERA_D3, + [4] = SPARKBOT_CAMERA_D4, + [5] = SPARKBOT_CAMERA_D5, + [6] = SPARKBOT_CAMERA_D6, + [7] = SPARKBOT_CAMERA_D7, + }, + .vsync_io = SPARKBOT_CAMERA_VSYNC, + .de_io = SPARKBOT_CAMERA_HSYNC, + .pclk_io = SPARKBOT_CAMERA_PCLK, + .xclk_io = SPARKBOT_CAMERA_XCLK, + }; + + // 复用 I2C 总线 + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, // 不初始化新的 SCCB,使用现有的 I2C 总线 + .i2c_handle = i2c_bus_, // 使用现有的 I2C 总线句柄 + .freq = 100000, // 100kHz + }; + + // DVP configuration + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = SPARKBOT_CAMERA_RESET, + .pwdn_pin = SPARKBOT_CAMERA_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = SPARKBOT_CAMERA_XCLK_FREQ, + }; + + // Main video configuration + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + + Settings settings("sparkbot", false); + // 考虑到部分复刻使用了不可动摄像头的设计,默认启用翻转 + bool camera_flipped = static_cast(settings.GetInt("camera-flipped", 1)); + camera_->SetHMirror(camera_flipped); + camera_->SetVFlip(camera_flipped); + } + + /* + ESP-SparkBot 的底座 + https://gitee.com/esp-friends/esp_sparkbot/tree/master/example/tank/c2_tracked_chassis + */ + void InitializeEchoUart() { + uart_config_t uart_config = { + .baud_rate = ECHO_UART_BAUD_RATE, + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, + .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, + .source_clk = UART_SCLK_DEFAULT, + }; + int intr_alloc_flags = 0; + + ESP_ERROR_CHECK(uart_driver_install(ECHO_UART_PORT_NUM, BUF_SIZE * 2, 0, 0, NULL, intr_alloc_flags)); + ESP_ERROR_CHECK(uart_param_config(ECHO_UART_PORT_NUM, &uart_config)); + ESP_ERROR_CHECK(uart_set_pin(ECHO_UART_PORT_NUM, UART_ECHO_TXD, UART_ECHO_RXD, UART_ECHO_RTS, UART_ECHO_CTS)); + + SendUartMessage("w2"); + } + + void SendUartMessage(const char * command_str) { + uint8_t len = strlen(command_str); + uart_write_bytes(ECHO_UART_PORT_NUM, command_str, len); + ESP_LOGI(TAG, "Sent command: %s", command_str); + } + + void InitializeTools() { + auto& mcp_server = McpServer::GetInstance(); + // 定义设备的属性 + mcp_server.AddTool("self.chassis.get_light_mode", "获取灯光效果编号", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + if (light_mode_ < 2) { + return 1; + } else { + return light_mode_ - 2; + } + }); + + mcp_server.AddTool("self.chassis.go_forward", "前进", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SendUartMessage("x0.0 y1.0"); + return true; + }); + + mcp_server.AddTool("self.chassis.go_back", "后退", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SendUartMessage("x0.0 y-1.0"); + return true; + }); + + mcp_server.AddTool("self.chassis.turn_left", "向左转", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SendUartMessage("x-1.0 y0.0"); + return true; + }); + + mcp_server.AddTool("self.chassis.turn_right", "向右转", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SendUartMessage("x1.0 y0.0"); + return true; + }); + + mcp_server.AddTool("self.chassis.dance", "跳舞", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + SendUartMessage("d1"); + light_mode_ = LIGHT_MODE_MAX; + return true; + }); + + mcp_server.AddTool("self.chassis.switch_light_mode", "打开灯光效果", PropertyList({ + Property("light_mode", kPropertyTypeInteger, 1, 6) + }), [this](const PropertyList& properties) -> ReturnValue { + char command_str[5] = {'w', 0, 0}; + char mode = static_cast(properties["light_mode"].value()); + + ESP_LOGI(TAG, "Switch Light Mode: %c", (mode + '0')); + + if (mode >= 3 && mode <= 8) { + command_str[1] = mode + '0'; + SendUartMessage(command_str); + return true; + } + throw std::runtime_error("Invalid light mode"); + }); + + mcp_server.AddTool("self.camera.set_camera_flipped", "翻转摄像头图像方向", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + Settings settings("sparkbot", true); + // 考虑到部分复刻使用了不可动摄像头的设计,默认启用翻转 + bool flipped = !static_cast(settings.GetInt("camera-flipped", 1)); + + camera_->SetHMirror(flipped); + camera_->SetVFlip(flipped); + + settings.SetInt("camera-flipped", flipped ? 1 : 0); + + return true; + }); + } + +public: + EspSparkBot() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeDisplay(); + InitializeButtons(); + InitializeCamera(); + InitializeEchoUart(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static SparkBotEs8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(EspSparkBot); diff --git a/main/boards/esp-spot/README.md b/main/boards/esp-spot/README.md new file mode 100644 index 0000000..c13054f --- /dev/null +++ b/main/boards/esp-spot/README.md @@ -0,0 +1,63 @@ +# ESP-Spot + +## 简介 + + + +ESP-Spot 是 ESP Friends 开源的一款智能语音交互盒子,内置麦克风、扬声器、IMU 惯性传感器,可使用电池供电。ESP-Spot 不带屏幕,带有一个 RGB 指示灯和两个按钮。硬件详情可查看[立创开源项目](https://oshwhub.com/esp-college/esp-spot)。 + +ESP-Spot 开源项目采用 ESP32-S3-WROOM-1-N16R8 模组或 ESP32-C5-WROOM-1-N8R8。如在复刻时使用了其他大小的 Flash,需修改对应的参数。 + + +## 配置、编译命令 + +**配置编译目标** + +```bash +idf.py set-target esp32s3 # Spot S3 +# or +idf.py set-target esp32c5 # Spot C5 +``` + +**打开 menuconfig 并配置** + +```bash +idf.py menuconfig +``` + +分别配置如下选项: + +- `Xiaozhi Assistant` → `Board Type` → 选择 `ESP-Spot-S3` / `ESP-Spot-C5` + +按 `S` 保存,按 `Q` 退出。 + +**编译** + +```bash +idf.py build +``` + +**烧录** + +```bash +idf.py flash +``` + +> [!TIP] +> +> **若电脑始终无法找到 ESP-Spot 串口,可尝试如下步骤** +> 1. 打开前盖; +> 2. 拔出带有模组的 PCB 板; +> 3. 按住 BOOT 同时插回 PCB 版,注意不要颠倒; +> +> 此时, ESP-Spot 应当已进入下载模式。在烧录完成后,可能需要重新插拔 PCB 板。 + +## 低功耗 + +ESP-Spot 支持 Deep Sleep 低功耗模式。 + +当处于 idle 状态 10 分钟后,ESP-Spot 会自动进入 Deep Sleep 模式,按 Key 键或摇晃 ESP-Spot 即可唤醒。 diff --git a/main/boards/esp-spot/config.h b/main/boards/esp-spot/config.h new file mode 100644 index 0000000..df6427d --- /dev/null +++ b/main/boards/esp-spot/config.h @@ -0,0 +1,79 @@ +#pragma once + +#include +#include "sdkconfig.h" + +/* Audio configuration */ +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 +#define AUDIO_INPUT_REFERENCE false +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +/* ADC configuration */ +#define ADC_ATTEN ADC_ATTEN_DB_12 +#define ADC_WIDTH ADC_BITWIDTH_DEFAULT +#define FULL_BATTERY_VOLTAGE 4100 +#define EMPTY_BATTERY_VOLTAGE 3200 + +/* I2C configuration */ +#define I2C_MASTER_FREQ_HZ (400 * 1000) + +/* Button configuration */ +#define LONG_PRESS_TIMEOUT_US (5 * 1000000ULL) + +#ifdef CONFIG_IDF_TARGET_ESP32S3 + +/* Audio I2S GPIOs */ +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_17 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_18 + +/* Audio CODEC GPIOs */ +#define AUDIO_CODEC_PA_PIN GPIO_NUM_40 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_2 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 + +/* Button GPIOs */ +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define KEY_BUTTON_GPIO GPIO_NUM_12 +#define LED_GPIO GPIO_NUM_11 + +/* ADC GPIOs */ +#define VBAT_ADC_CHANNEL ADC_CHANNEL_9 // S3: IO10 +#define MCU_VCC_CTL GPIO_NUM_4 // set 1 to power on MCU +#define PERP_VCC_CTL GPIO_NUM_6 // set 1 to power on peripherals + +/* IMU GPIOs */ +#define IMU_INT_GPIO GPIO_NUM_5 + +#elif defined(CONFIG_IDF_TARGET_ESP32C5) + +/* Audio I2S GPIOs */ +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_NC +#define AUDIO_I2S_GPIO_WS GPIO_NUM_8 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +/* Audio CODEC GPIOs */ +#define AUDIO_CODEC_PA_PIN GPIO_NUM_23 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_25 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_26 + +/* Button GPIOs */ +#define BOOT_BUTTON_GPIO GPIO_NUM_28 +#define KEY_BUTTON_GPIO GPIO_NUM_5 +#define LED_GPIO GPIO_NUM_27 + +/* ADC GPIOs */ +#define VBAT_ADC_CHANNEL ADC_CHANNEL_3 // C5: IO4 +#define MCU_VCC_CTL GPIO_NUM_2 // set 1 to power on MCU +#define PERP_VCC_CTL GPIO_NUM_0 // set 1 to power on peripherals + +/* IMU GPIOs */ +#define IMU_INT_GPIO GPIO_NUM_3 + +#endif // CONFIG_IDF_TARGET + diff --git a/main/boards/esp-spot/config.json b/main/boards/esp-spot/config.json new file mode 100644 index 0000000..350171e --- /dev/null +++ b/main/boards/esp-spot/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32c5", + "builds": [ + { + "name": "esp-spot-c5", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp-spot/esp_spot_board.cc b/main/boards/esp-spot/esp_spot_board.cc new file mode 100644 index 0000000..9cc6294 --- /dev/null +++ b/main/boards/esp-spot/esp_spot_board.cc @@ -0,0 +1,437 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include "esp_idf_version.h" +#include "led/circular_strip.h" +#include "sdkconfig.h" + +#include "application.h" +#include "button.h" +#include "codecs/es8311_audio_codec.h" +#include "config.h" +#include "sleep_timer.h" +#include "wifi_board.h" +#include "wifi_station.h" + +#ifdef IMU_INT_GPIO +#include + +#include "bmi270_api.h" +#include "i2c_bus.h" +#endif // IMU_INT_GPIO + +#ifdef CONFIG_IDF_TARGET_ESP32S3 +#define TAG "esp_spot_s3" +#elif defined(CONFIG_IDF_TARGET_ESP32C5) +#define TAG "esp_spot_c5" +#else // target +#error "Unsupported target" +#endif // target + +#ifdef IMU_INT_GPIO +namespace Bmi270Imu { + +static bmi270_handle_t bmi_handle_ = nullptr; + +esp_err_t Initialize(i2c_bus_handle_t i2c_bus, uint8_t addr = BMI270_I2C_ADDRESS) { + if (bmi_handle_) { + return ESP_OK; + } + + if (!i2c_bus) { + ESP_LOGE(TAG, "Invalid I2C bus for BMI270"); + return ESP_ERR_INVALID_ARG; + } + + esp_err_t ret = bmi270_sensor_create(i2c_bus, &bmi_handle_, bmi270_config_file, + BMI2_GYRO_CROSS_SENS_ENABLE | BMI2_CRT_RTOSK_ENABLE); + if (ret != ESP_OK || !bmi_handle_) { + ESP_LOGE(TAG, "BMI270 create failed: %s", esp_err_to_name(ret)); + return ret == ESP_OK ? ESP_FAIL : ret; + } + ESP_LOGI(TAG, "BMI270 initialized"); + return ESP_OK; +} + +// Only used for deep sleep wakeup with wrist gesture interrupt +esp_err_t EnableImuIntForWakeup() { + if (!bmi_handle_) { + return ESP_ERR_INVALID_STATE; + } + + const uint8_t sens_list[] = {BMI2_ACCEL, BMI2_WRIST_GESTURE}; + int8_t rslt = bmi270_sensor_enable(sens_list, 2, bmi_handle_); + if (rslt != BMI2_OK) { + ESP_LOGE(TAG, "Failed to enable BMI270 sensors: %d", rslt); + return ESP_FAIL; + } + + struct bmi2_sens_config config = {.type = BMI2_WRIST_GESTURE}; + rslt = bmi270_get_sensor_config(&config, 1, bmi_handle_); + if (rslt != BMI2_OK) { + ESP_LOGE(TAG, "Failed to get wrist gesture config: %d", rslt); + return ESP_FAIL; + } + config.cfg.wrist_gest.wearable_arm = BMI2_ARM_RIGHT; + rslt = bmi270_set_sensor_config(&config, 1, bmi_handle_); + if (rslt != BMI2_OK) { + ESP_LOGE(TAG, "Failed to set wrist gesture config: %d", rslt); + return ESP_FAIL; + } + + struct bmi2_int_pin_config pin_config = {}; + pin_config.pin_type = BMI2_INT1; + pin_config.pin_cfg[0].input_en = BMI2_INT_INPUT_DISABLE; + pin_config.pin_cfg[0].lvl = BMI2_INT_ACTIVE_HIGH; + pin_config.pin_cfg[0].od = BMI2_INT_PUSH_PULL; + pin_config.pin_cfg[0].output_en = BMI2_INT_OUTPUT_ENABLE; + pin_config.int_latch = BMI2_INT_NON_LATCH; + rslt = bmi2_set_int_pin_config(&pin_config, bmi_handle_); + if (rslt != BMI2_OK) { + ESP_LOGE(TAG, "Failed to set BMI270 INT pin: %d", rslt); + return ESP_FAIL; + } + + struct bmi2_sens_int_config int_config = {.type = BMI2_WRIST_GESTURE, .hw_int_pin = BMI2_INT1}; + rslt = bmi270_map_feat_int(&int_config, 1, bmi_handle_); + if (rslt != BMI2_OK) { + ESP_LOGE(TAG, "Failed to map BMI270 interrupt: %d", rslt); + return ESP_FAIL; + } + + return ESP_OK; +} + +} // namespace Bmi270Imu + +#endif // IMU_INT_GPIO + +class EspSpot : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_ = nullptr; + Button boot_button_; + Button key_button_; + adc_oneshot_unit_handle_t adc1_handle_; + adc_cali_handle_t adc1_cali_handle_; + bool adc_calibration_lock_ = false; + bool key_long_pressed_ = false; + int64_t last_key_press_time = 0; + SleepTimer* sleep_timer_ = nullptr; +#ifdef IMU_INT_GPIO + i2c_bus_handle_t shared_i2c_bus_handle_ = nullptr; + static constexpr int kDeepSleepTimeoutSeconds = 10 * 60; // 10 minutes + bool imu_ready_ = false; +#endif + +#ifdef IMU_INT_GPIO + void InitializeI2c() { + // Initialize I2C peripheral + i2c_config_t i2c_bus_cfg = { + .mode = I2C_MODE_MASTER, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .sda_pullup_en = true, + .scl_pullup_en = true, + .master = + { + .clk_speed = I2C_MASTER_FREQ_HZ, + }, + .clk_flags = 0, + }; + shared_i2c_bus_handle_ = i2c_bus_create(I2C_NUM_0, &i2c_bus_cfg); + if (!shared_i2c_bus_handle_) { + ESP_LOGE(TAG, "Failed to create shared I2C bus"); + ESP_ERROR_CHECK(ESP_FAIL); + } + +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 3, 0) && !CONFIG_I2C_BUS_BACKWARD_CONFIG + i2c_bus_ = i2c_bus_get_internal_bus_handle(shared_i2c_bus_handle_); +#else +#error "ESP-Spot board requires i2c_bus_get_internal_bus_handle() support" +#endif + if (!i2c_bus_) { + ESP_LOGE(TAG, "Failed to obtain master bus handle"); + ESP_ERROR_CHECK(ESP_FAIL); + } + + esp_err_t imu_ret = Bmi270Imu::Initialize(shared_i2c_bus_handle_); + if (imu_ret != ESP_OK) { + ESP_LOGW(TAG, "BMI270 initialization failed, deep sleep disabled (%s)", esp_err_to_name(imu_ret)); + } else { + imu_ready_ = true; + } + } +#else + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = + { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } +#endif // IMU_INT_GPIO + + void InitializeADC() { + adc_oneshot_unit_init_cfg_t init_config1 = {.unit_id = ADC_UNIT_1}; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config1, &adc1_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN, + .bitwidth = ADC_WIDTH, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle_, VBAT_ADC_CHANNEL, &chan_config)); + +#ifdef ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED + adc_cali_handle_t handle = nullptr; + esp_err_t ret = ESP_FAIL; + + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = ADC_UNIT_1, + .atten = ADC_ATTEN, + .bitwidth = ADC_WIDTH, + }; + ret = adc_cali_create_scheme_curve_fitting(&cali_config, &handle); + if (ret == ESP_OK) { + adc_calibration_lock_ = true; + adc1_cali_handle_ = handle; + ESP_LOGI(TAG, "ADC Curve Fitting calibration succeeded"); + } +#endif // ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + HandleUserActivity(); + ResetWifiConfiguration(); + }); + + key_button_.OnClick([this]() { + HandleUserActivity(); + auto& app = Application::GetInstance(); + app.ToggleChatState(); + key_long_pressed_ = false; + }); + + key_button_.OnLongPress([this]() { + HandleUserActivity(); + int64_t now = esp_timer_get_time(); + auto* led = static_cast(this->GetLed()); + + if (key_long_pressed_) { + if ((now - last_key_press_time) < LONG_PRESS_TIMEOUT_US) { + ESP_LOGW(TAG, "Key button long pressed the second time within 5s, shutting down..."); + led->SetSingleColor(0, {0, 0, 0}); + + gpio_hold_dis(MCU_VCC_CTL); + gpio_set_level(MCU_VCC_CTL, 0); + + } else { + last_key_press_time = now; + BlinkGreenFor5s(); + } + key_long_pressed_ = true; + } else { + ESP_LOGW(TAG, "Key button first long press! Waiting second within 5s to shutdown..."); + last_key_press_time = now; + key_long_pressed_ = true; + + BlinkGreenFor5s(); + } + }); + } + + void InitializePowerCtl() { + InitializeGPIO(); + + gpio_set_level(MCU_VCC_CTL, 1); + gpio_hold_en(MCU_VCC_CTL); + + gpio_set_level(PERP_VCC_CTL, 1); + gpio_hold_en(PERP_VCC_CTL); + } + + void InitializeGPIO() { + gpio_config_t io_pa = {.pin_bit_mask = (1ULL << AUDIO_CODEC_PA_PIN), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE}; + gpio_config(&io_pa); + gpio_set_level(AUDIO_CODEC_PA_PIN, 0); + + gpio_config_t io_conf_1 = {.pin_bit_mask = (1ULL << MCU_VCC_CTL), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE}; + gpio_config(&io_conf_1); + + gpio_config_t io_conf_2 = {.pin_bit_mask = (1ULL << PERP_VCC_CTL), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE}; + gpio_config(&io_conf_2); + +#ifdef IMU_INT_GPIO + gpio_config_t io_conf_imu_int = { + .pin_bit_mask = (1ULL << IMU_INT_GPIO), + .mode = GPIO_MODE_INPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_ENABLE, + .intr_type = GPIO_INTR_NEGEDGE, + }; + gpio_config(&io_conf_imu_int); + gpio_install_isr_service(0); +#endif // IMU_INT_GPIO + } + + void HandleUserActivity() { + if (sleep_timer_) { + sleep_timer_->WakeUp(); + } + } + +#ifdef IMU_INT_GPIO + void InitializePowerSaveTimer() { + if (!imu_ready_) { + ESP_LOGW(TAG, "IMU not ready, skip deep sleep timer"); + return; + } + if (sleep_timer_) { + return; + } + sleep_timer_ = new SleepTimer(-1, kDeepSleepTimeoutSeconds); + sleep_timer_->OnEnterDeepSleepMode([this]() { EnterDeepSleep(); }); + sleep_timer_->SetEnabled(true); + ESP_LOGI(TAG, "Deep sleep timer enabled, timeout=%ds", kDeepSleepTimeoutSeconds); + } + + void EnterDeepSleep() { + if (!imu_ready_) { + ESP_LOGW(TAG, "Skip deep sleep because IMU is not ready"); + return; + } + + auto* led = static_cast(GetLed()); + if (led) { + led->SetSingleColor(0, {0, 0, 0}); + } + + if (Bmi270Imu::EnableImuIntForWakeup() != ESP_OK) { + ESP_LOGE(TAG, "IMU wakeup configuration failed, abort deep sleep"); + return; + } + + const uint64_t wakeup_mask = (1ULL << KEY_BUTTON_GPIO) | (1ULL << IMU_INT_GPIO); + ESP_ERROR_CHECK(esp_sleep_enable_ext1_wakeup(wakeup_mask, ESP_EXT1_WAKEUP_ANY_HIGH)); + ESP_LOGI(TAG, "Entering deep sleep, waiting for key or wrist gesture"); + esp_deep_sleep_start(); + } +#endif // IMU_INT_GPIO + + void BlinkGreenFor5s() { + auto* led = static_cast(GetLed()); + if (!led) { + return; + } + + led->Blink({50, 25, 0}, 100); + + esp_timer_create_args_t timer_args = {.callback = + [](void* arg) { + auto* self = static_cast(arg); + auto* led = static_cast(self->GetLed()); + if (led) { + led->SetSingleColor(0, {0, 0, 0}); + } + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "green_blink_timer"}; + + esp_timer_handle_t green_blink_timer = nullptr; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &green_blink_timer)); + ESP_ERROR_CHECK(esp_timer_start_once(green_blink_timer, LONG_PRESS_TIMEOUT_US)); + } + +public: + EspSpot() : boot_button_(BOOT_BUTTON_GPIO), key_button_(KEY_BUTTON_GPIO, true) { + InitializePowerCtl(); + InitializeADC(); + InitializeI2c(); + InitializeButtons(); +#ifdef IMU_INT_GPIO + InitializePowerSaveTimer(); +#endif // IMU_INT_GPIO + } + + virtual Led* GetLed() override { + static CircularStrip led(LED_GPIO, 1); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, false); + return &audio_codec; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (sleep_timer_) { + sleep_timer_->SetEnabled(enabled); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + if (!adc1_handle_) { + InitializeADC(); + } + + int raw_value = 0; + int voltage = 0; + + ESP_ERROR_CHECK(adc_oneshot_read(adc1_handle_, VBAT_ADC_CHANNEL, &raw_value)); + + if (adc_calibration_lock_) { + ESP_ERROR_CHECK(adc_cali_raw_to_voltage(adc1_cali_handle_, raw_value, &voltage)); + voltage = voltage * 3 / 2; // compensate for voltage divider + ESP_LOGI(TAG, "Calibrated voltage: %d mV", voltage); + } else { + ESP_LOGI(TAG, "Raw ADC value: %d", raw_value); + voltage = raw_value; + } + + voltage = voltage < EMPTY_BATTERY_VOLTAGE ? EMPTY_BATTERY_VOLTAGE : voltage; + voltage = voltage > FULL_BATTERY_VOLTAGE ? FULL_BATTERY_VOLTAGE : voltage; + + // Calculate battery level percentage + level = (voltage - EMPTY_BATTERY_VOLTAGE) * 100 / (FULL_BATTERY_VOLTAGE - EMPTY_BATTERY_VOLTAGE); + + // ESP-Spot does not support charging detection, so we use MCU_VCC_CTL to determine charging status + charging = gpio_get_level(MCU_VCC_CTL); + discharging = !charging; + ESP_LOGI(TAG, "Battery Level: %d%%, Charging: %s", level, charging ? "Yes" : "No"); + return true; + } +}; + +DECLARE_BOARD(EspSpot); diff --git a/main/boards/esp32-cgc-144/README.md b/main/boards/esp32-cgc-144/README.md new file mode 100644 index 0000000..fcd8758 --- /dev/null +++ b/main/boards/esp32-cgc-144/README.md @@ -0,0 +1,30 @@ +# 相关资料: +- [插线款](https://www.wdmomo.fun:81/doc/index.html?file=001_%E8%AE%BE%E8%AE%A1%E9%A1%B9%E7%9B%AE/0001_%E5%B0%8F%E6%99%BAAI/003_ESP32-CGC-144%E6%8F%92%E7%BA%BF%E7%89%88%E5%B0%8F%E6%99%BAAI) + +- [电池款](https://www.wdmomo.fun:81/doc/index.html?file=001_%E8%AE%BE%E8%AE%A1%E9%A1%B9%E7%9B%AE/0001_%E5%B0%8F%E6%99%BAAI/004_ESP32-CGC-144%E7%94%B5%E6%B1%A0%E7%89%88%E5%B0%8F%E6%99%BAAI) + +# 编译配置命令 + +**配置编译目标为 ESP32:** + +```bash +idf.py set-target esp32 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> ESP32 CGC 144 +``` + +**编译:** + +```bash +idf.py build +``` diff --git a/main/boards/esp32-cgc-144/config.h b/main/boards/esp32-cgc-144/config.h new file mode 100644 index 0000000..6a23386 --- /dev/null +++ b/main/boards/esp32-cgc-144/config.h @@ -0,0 +1,73 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +// 如果使用插线版本接入电池,请启用下面一行 +//#define ESP32_CGC_144_lite + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_25 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_26 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_32 + +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_33 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_27 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define ASR_BUTTON_GPIO GPIO_NUM_13 + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_12 + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_4 +#define DISPLAY_SCLK_PIN GPIO_NUM_18 +#define DISPLAY_MOSI_PIN GPIO_NUM_23 +#define DISPLAY_CS_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_2 +#define DISPLAY_RESET_PIN GPIO_NUM_NC + +#define DISPLAY_SPI_SCLK_HZ (20 * 1000 * 1000) + +// 如果使用240x240的屏幕,请注释下面一行 +#define LCD_128X128 + +#ifdef LCD_128X128 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 2 +#define DISPLAY_OFFSET_Y 3 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true +#define DISPLAY_SPI_MODE 0 + +#else + +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true +#define DISPLAY_SPI_MODE 0 + +#endif + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-cgc-144/config.json b/main/boards/esp32-cgc-144/config.json new file mode 100644 index 0000000..ca42e8a --- /dev/null +++ b/main/boards/esp32-cgc-144/config.json @@ -0,0 +1,10 @@ +{ + "target": "esp32", + "builds": [ + { + "name": "esp32-cgc-144", + "sdkconfig_append": [ + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-cgc-144/esp32_cgc_144_board.cc b/main/boards/esp32-cgc-144/esp32_cgc_144_board.cc new file mode 100644 index 0000000..25963c0 --- /dev/null +++ b/main/boards/esp32-cgc-144/esp32_cgc_144_board.cc @@ -0,0 +1,192 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#include + +#if defined(ESP32_CGC_144_lite) +#include "power_manager_lite.h" +#else +#include "power_manager.h" +#endif + +#define TAG "ESP32_CGC_144" + +class ESP32_CGC_144 : public WifiBoard { +private: + Button boot_button_; + LcdDisplay* display_; + Button asr_button_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + +#if defined(ESP32_CGC_144_lite) +void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_NC); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); +} +#else +void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_36); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); +} +#endif + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeSt7735Display() { + // esp_lcd_panel_io_handle_t panel_io = nullptr; + // esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RESET_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + asr_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + std::string wake_word="你好小智"; + Application::GetInstance().WakeWordInvoke(wake_word); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + ESP32_CGC_144() : + boot_button_(BOOT_BUTTON_GPIO), asr_button_(ASR_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeSt7735Display(); + InitializeButtons(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(ESP32_CGC_144); diff --git a/main/boards/esp32-cgc-144/power_manager.h b/main/boards/esp32-cgc-144/power_manager.h new file mode 100644 index 0000000..9576e30 --- /dev/null +++ b/main/boards/esp32-cgc-144/power_manager.h @@ -0,0 +1,186 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_3, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1970, 0}, + {2062, 20}, + {2154, 40}, + {2246, 60}, + {2338, 80}, + {2430, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_3, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/esp32-cgc-144/power_manager_lite.h b/main/boards/esp32-cgc-144/power_manager_lite.h new file mode 100644 index 0000000..f088286 --- /dev/null +++ b/main/boards/esp32-cgc-144/power_manager_lite.h @@ -0,0 +1,185 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); //lite + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // lite定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {3000, 0}, + {3160, 20}, + {3320, 40}, + {3480, 60}, + {3640, 80}, + {3800, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); //lite + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/esp32-cgc/README.md b/main/boards/esp32-cgc/README.md new file mode 100644 index 0000000..3a40900 --- /dev/null +++ b/main/boards/esp32-cgc/README.md @@ -0,0 +1,36 @@ +# 主板开源地址: +- V1:[https://oshwhub.com/wdmomo/esp32-xiaozhi-kidpcb](https://oshwhub.com/wdmomo/esp32-xiaozhi-kidpcb) +- V2:[https://oshwhub.com/wdmomo/esp32-xiaozhi-kidpcb_copy](https://oshwhub.com/wdmomo/esp32-xiaozhi-kidpcb_copy) +- 更多介绍:[wdmomo.fun](https://www.wdmomo.fun:81/doc/index.html?file=001_%E8%AE%BE%E8%AE%A1%E9%A1%B9%E7%9B%AE/0001_%E5%B0%8F%E6%99%BAAI/002_ESP32-CGC%E5%BC%80%E5%8F%91%E6%9D%BF%E5%B0%8F%E6%99%BAAI) + +# 编译配置命令 + +**配置编译目标为 ESP32:** + +```bash +idf.py set-target esp32 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> ESP32 CGC +``` + +**选择屏幕类型:** + +``` +Xiaozhi Assistant -> LCD Type -> "ST7735, 分辨率128*128" +``` + +**编译:** + +```bash +idf.py build +``` diff --git a/main/boards/esp32-cgc/config.h b/main/boards/esp32-cgc/config.h new file mode 100644 index 0000000..2e27571 --- /dev/null +++ b/main/boards/esp32-cgc/config.h @@ -0,0 +1,271 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +// 如果使用 Duplex I2S 模式,请注释下面一行 +#define AUDIO_I2S_METHOD_SIMPLEX + +#ifdef AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_25 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_26 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_32 + +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_33 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_27 + +#else + +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_7 + +#endif + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define ASR_BUTTON_GPIO GPIO_NUM_13 + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_12 + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_4 +#define DISPLAY_SCLK_PIN GPIO_NUM_18 +#define DISPLAY_MOSI_PIN GPIO_NUM_23 +#define DISPLAY_CS_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_2 +#define DISPLAY_RESET_PIN GPIO_NUM_NC + +#define DISPLAY_SPI_SCLK_HZ (20 * 1000 * 1000) + +#ifdef CONFIG_LCD_ST7789_240X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif + +#ifdef CONFIG_LCD_ST7789_240X320_NO_IPS +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_170X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 170 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 35 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_172X320 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 172 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 34 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X280 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7789_240X240_7PIN +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 2 +#endif + +#ifdef CONFIG_LCD_ST7789_240X135 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 135 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 40 +#define DISPLAY_OFFSET_Y 53 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7735_128X160 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif + +#ifdef CONFIG_LCD_ST7735_128X128 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 2 +#define DISPLAY_OFFSET_Y 3 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ST7796_320X480 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 480 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320 +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_ILI9341_240X320_NO_IPS +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_GC9A01_240X240 +#define LCD_TYPE_GC9A01_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#ifdef CONFIG_LCD_CUSTOM +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 0 +#endif + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-cgc/config.json b/main/boards/esp32-cgc/config.json new file mode 100644 index 0000000..a8a1629 --- /dev/null +++ b/main/boards/esp32-cgc/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32", + "builds": [ + { + "name": "esp32-cgc", + "sdkconfig_append": [ + "CONFIG_LCD_ST7735_128X128=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-cgc/esp32_cgc_board.cc b/main/boards/esp32-cgc/esp32_cgc_board.cc new file mode 100644 index 0000000..6b82b01 --- /dev/null +++ b/main/boards/esp32-cgc/esp32_cgc_board.cc @@ -0,0 +1,180 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include +#include +#include + +#if defined(LCD_TYPE_ILI9341_SERIAL) +#include +#endif + +#if defined(LCD_TYPE_GC9A01_SERIAL) +#include +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; +#endif + +#define TAG "ESP32_CGC" + +class ESP32_CGC : public WifiBoard { +private: + Button boot_button_; + LcdDisplay* display_; + Button asr_button_; + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RESET_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; +#if defined(LCD_TYPE_ILI9341_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); +#elif defined(LCD_TYPE_GC9A01_SERIAL) + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel)); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; +#else + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); +#endif + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); +#ifdef LCD_TYPE_GC9A01_SERIAL + panel_config.vendor_config = &gc9107_vendor_config; +#endif + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + asr_button_.OnClick([this]() { + std::string wake_word="你好小智"; + Application::GetInstance().WakeWordInvoke(wake_word); + }); + + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + ESP32_CGC() : + boot_button_(BOOT_BUTTON_GPIO), asr_button_(ASR_BUTTON_GPIO) { + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override + { +#ifdef AUDIO_I2S_METHOD_SIMPLEX + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); +#else + static NoAudioCodecDuplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(ESP32_CGC); diff --git a/main/boards/esp32-s3-touch-amoled-1.8/config.h b/main/boards/esp32-s3-touch-amoled-1.8/config.h new file mode 100644 index 0000000..c904053 --- /dev/null +++ b/main/boards/esp32-s3-touch-amoled-1.8/config.h @@ -0,0 +1,41 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define EXAMPLE_PIN_NUM_LCD_CS GPIO_NUM_12 +#define EXAMPLE_PIN_NUM_LCD_PCLK GPIO_NUM_11 +#define EXAMPLE_PIN_NUM_LCD_DATA0 GPIO_NUM_4 +#define EXAMPLE_PIN_NUM_LCD_DATA1 GPIO_NUM_5 +#define EXAMPLE_PIN_NUM_LCD_DATA2 GPIO_NUM_6 +#define EXAMPLE_PIN_NUM_LCD_DATA3 GPIO_NUM_7 +#define EXAMPLE_PIN_NUM_LCD_RST GPIO_NUM_NC +#define DISPLAY_WIDTH 368 +#define DISPLAY_HEIGHT 448 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-s3-touch-amoled-1.8/config.json b/main/boards/esp32-s3-touch-amoled-1.8/config.json new file mode 100644 index 0000000..6719497 --- /dev/null +++ b/main/boards/esp32-s3-touch-amoled-1.8/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32-s3-touch-amoled-1.8", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-amoled-1.8/esp32-s3-touch-amoled-1.8.cc b/main/boards/esp32-s3-touch-amoled-1.8/esp32-s3-touch-amoled-1.8.cc new file mode 100644 index 0000000..111f61f --- /dev/null +++ b/main/boards/esp32-s3-touch-amoled-1.8/esp32-s3-touch-amoled-1.8.cc @@ -0,0 +1,335 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" + +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" +#include "settings.h" + +#include +#include +#include + +#define TAG "WaveshareEsp32s3TouchAMOLED1inch8" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x01); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x03ULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const sh8601_lcd_init_cmd_t vendor_specific_init[] = { + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0x44, (uint8_t[]){0x01, 0xD1}, 2, 0}, + {0x35, (uint8_t[]){0x00}, 1, 0}, + {0x53, (uint8_t[]){0x20}, 1, 10}, + {0x2A, (uint8_t[]){0x00, 0x00, 0x01, 0x6F}, 4, 0}, + {0x2B, (uint8_t[]){0x00, 0x00, 0x01, 0xBF}, 4, 0}, + {0x51, (uint8_t[]){0x00}, 1, 10}, + {0x29, (uint8_t[]){0x00}, 0, 10} +}; + +// 在waveshare_amoled_1_8类之前添加新的显示类 +class CustomLcdDisplay : public SpiLcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES * 0.1, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES * 0.1, 0); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(esp_lcd_panel_io_handle_t panel_io) : Backlight(), panel_io_(panel_io) {} + +protected: + esp_lcd_panel_io_handle_t panel_io_; + + virtual void SetBrightnessImpl(uint8_t brightness) override { + auto display = Board::GetInstance().GetDisplay(); + DisplayLockGuard lock(display); + uint8_t data[1] = {((uint8_t)((255 * brightness) / 100))}; + int lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_WRITE_CMD << 24; + esp_lcd_panel_io_tx_param(panel_io_, lcd_cmd, &data, sizeof(data)); + } +}; + +class WaveshareEsp32s3TouchAMOLED1inch8 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + CustomLcdDisplay* display_; + CustomBacklight* backlight_; + esp_io_expander_handle_t io_expander = NULL; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(codec_i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 |IO_EXPANDER_PIN_NUM_2, IO_EXPANDER_OUTPUT); + ret |= esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_4, IO_EXPANDER_INPUT); + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1|IO_EXPANDER_PIN_NUM_2, 1); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1|IO_EXPANDER_PIN_NUM_2, 0); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1|IO_EXPANDER_PIN_NUM_2, 1); + ESP_ERROR_CHECK(ret); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(codec_i2c_bus_, 0x34); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.sclk_io_num = GPIO_NUM_11; + buscfg.data0_io_num = GPIO_NUM_4; + buscfg.data1_io_num = GPIO_NUM_5; + buscfg.data2_io_num = GPIO_NUM_6; + buscfg.data3_io_num = GPIO_NUM_7; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + buscfg.flags = SPICOMMON_BUSFLAG_QUAD; + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeSH8601Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = SH8601_PANEL_IO_QSPI_CONFIG( + EXAMPLE_PIN_NUM_LCD_CS, + nullptr, + nullptr + ); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const sh8601_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(sh8601_lcd_init_cmd_t), + .flags ={ + .use_qspi_interface = 1, + } + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.flags.reset_active_high = 1, + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *)&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + backlight_ = new CustomBacklight(panel_io); + backlight_->RestoreBrightness(); + } + + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_21, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_FT5x06_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(codec_i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_ft5x06(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + WaveshareEsp32s3TouchAMOLED1inch8() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeTca9554(); + InitializeAxp2101(); + InitializeSpi(); + InitializeSH8601Display(); + InitializeTouch(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + return backlight_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32s3TouchAMOLED1inch8); diff --git a/main/boards/esp32-s3-touch-lcd-1.46/README.md b/main/boards/esp32-s3-touch-lcd-1.46/README.md new file mode 100644 index 0000000..0919b9d --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.46/README.md @@ -0,0 +1,4 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-1.46、ESP32-S3-Touch-LCD-1.46B +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-1.46.htm +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-1.46B.htm \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.46/config.h b/main/boards/esp32-s3-touch-lcd-1.46/config.h new file mode 100644 index 0000000..b1bd2d9 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.46/config.h @@ -0,0 +1,70 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_6 +#define PWR_Control_PIN GPIO_NUM_7 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_2 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_15 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_47 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_48 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_38 + +#define I2C_SCL_IO GPIO_NUM_10 +#define I2C_SDA_IO GPIO_NUM_11 + + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 + +#define DISPLAY_WIDTH 412 +#define DISPLAY_HEIGHT 412 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define QSPI_LCD_H_RES (412) +#define QSPI_LCD_V_RES (412) +#define QSPI_LCD_BIT_PER_PIXEL (16) + +#define QSPI_LCD_HOST SPI2_HOST +#define QSPI_PIN_NUM_LCD_PCLK GPIO_NUM_40 +#define QSPI_PIN_NUM_LCD_CS GPIO_NUM_21 +#define QSPI_PIN_NUM_LCD_DATA0 GPIO_NUM_46 +#define QSPI_PIN_NUM_LCD_DATA1 GPIO_NUM_45 +#define QSPI_PIN_NUM_LCD_DATA2 GPIO_NUM_42 +#define QSPI_PIN_NUM_LCD_DATA3 GPIO_NUM_41 +#define QSPI_PIN_NUM_LCD_RST GPIO_NUM_NC +#define QSPI_PIN_NUM_LCD_BL GPIO_NUM_5 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define TP_PORT (I2C_NUM_1) +#define TP_PIN_NUM_SDA (I2C_SDA_IO) +#define TP_PIN_NUM_SCL (I2C_SCL_IO) +#define TP_PIN_NUM_RST (GPIO_NUM_NC) +#define TP_PIN_NUM_INT (GPIO_NUM_4) + +#define DISPLAY_BACKLIGHT_PIN QSPI_PIN_NUM_LCD_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define TAIJIPI_SPD2010_PANEL_BUS_QSPI_CONFIG(sclk, d0, d1, d2, d3, max_trans_sz) \ + { \ + .data0_io_num = d0, \ + .data1_io_num = d1, \ + .sclk_io_num = sclk, \ + .data2_io_num = d2, \ + .data3_io_num = d3, \ + .max_transfer_sz = max_trans_sz, \ + } + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-s3-touch-lcd-1.46/config.json b/main/boards/esp32-s3-touch-lcd-1.46/config.json new file mode 100644 index 0000000..e7e5852 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.46/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32-s3-touch-lcd-1.46", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.46/esp32-s3-touch-lcd-1.46.cc b/main/boards/esp32-s3-touch-lcd-1.46/esp32-s3-touch-lcd-1.46.cc new file mode 100644 index 0000000..90843e6 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.46/esp32-s3-touch-lcd-1.46.cc @@ -0,0 +1,237 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" +#include "lcd_display.h" +#include + +#define TAG "waveshare_lcd_1_46" + +// 在waveshare_lcd_1_46类之前添加新的显示类 +class CustomLcdDisplay : public SpiLcdDisplay { +public: + static void rounder_event_cb(lv_event_t * e) { + lv_area_t * area = (lv_area_t *)lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + + area->x1 = (x1 >> 2) << 2; // round the start of coordinate down to the nearest 4M number + area->x2 = ((x2 >> 2) << 2) + 3; // round the end of coordinate up to the nearest 4N+3 number + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_display_add_event_cb(display_, rounder_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + } +}; + +class CustomBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + button_handle_t boot_btn, pwr_btn; + button_driver_t* boot_btn_driver_ = nullptr; + button_driver_t* pwr_btn_driver_ = nullptr; + static CustomBoard* instance_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = I2C_SDA_IO, + .scl_io_num = I2C_SCL_IO, + .clk_source = I2C_CLK_SRC_DEFAULT, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + + // uint32_t input_level_mask = 0; + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_INPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输入 + // ret = esp_io_expander_get_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, &input_level_mask); // 获取引脚 EXIO0 和 EXIO1 的电平状态,存放在 input_level_mask 中 + + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO2 和 EXIO3 模式为输出 + // ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, 1); // 将引脚电平设置为 1 + // ret = esp_io_expander_print_state(io_expander); // 打印引脚状态 + + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输出 + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + + const spi_bus_config_t bus_config = TAIJIPI_SPD2010_PANEL_BUS_QSPI_CONFIG(QSPI_PIN_NUM_LCD_PCLK, + QSPI_PIN_NUM_LCD_DATA0, + QSPI_PIN_NUM_LCD_DATA1, + QSPI_PIN_NUM_LCD_DATA2, + QSPI_PIN_NUM_LCD_DATA3, + QSPI_LCD_H_RES * 80 * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(QSPI_LCD_HOST, &bus_config, SPI_DMA_CH_AUTO)); + } + + void InitializeSpd2010Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGI(TAG, "Install panel IO"); + + const esp_lcd_panel_io_spi_config_t io_config = SPD2010_PANEL_IO_QSPI_CONFIG(QSPI_PIN_NUM_LCD_CS, NULL, NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io)); + + ESP_LOGI(TAG, "Install SPD2010 panel driver"); + + spd2010_vendor_config_t vendor_config = { + .flags = { + .use_qspi_interface = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = QSPI_PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, // Implemented by LCD command `36h` + .bits_per_pixel = QSPI_LCD_BIT_PER_PIXEL, // Implemented by LCD command `3Ah` (16/18) + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_spd2010(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_disp_on_off(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtonsCustom() { + gpio_reset_pin(BOOT_BUTTON_GPIO); + gpio_set_direction(BOOT_BUTTON_GPIO, GPIO_MODE_INPUT); + gpio_reset_pin(PWR_BUTTON_GPIO); + gpio_set_direction(PWR_BUTTON_GPIO, GPIO_MODE_INPUT); + gpio_reset_pin(PWR_Control_PIN); + gpio_set_direction(PWR_Control_PIN, GPIO_MODE_OUTPUT); + // gpio_set_level(PWR_Control_PIN, false); + gpio_set_level(PWR_Control_PIN, true); + } + + void InitializeButtons() { + instance_ = this; + InitializeButtonsCustom(); + + // Boot Button + button_config_t boot_btn_config = { + .long_press_time = 2000, + .short_press_time = 0 + }; + boot_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + boot_btn_driver_->enable_power_save = false; + boot_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !gpio_get_level(BOOT_BUTTON_GPIO); + }; + ESP_ERROR_CHECK(iot_button_create(&boot_btn_config, boot_btn_driver_, &boot_btn)); + iot_button_register_cb(boot_btn, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + app.ToggleChatState(); + }, this); + iot_button_register_cb(boot_btn, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + // 长按无处理 + }, this); + + // Power Button + button_config_t pwr_btn_config = { + .long_press_time = 5000, + .short_press_time = 0 + }; + pwr_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + pwr_btn_driver_->enable_power_save = false; + pwr_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !gpio_get_level(PWR_BUTTON_GPIO); + }; + ESP_ERROR_CHECK(iot_button_create(&pwr_btn_config, pwr_btn_driver_, &pwr_btn)); + iot_button_register_cb(pwr_btn, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + // 短按无处理 + }, this); + iot_button_register_cb(pwr_btn, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + if(self->GetBacklight()->brightness() > 0) { + self->GetBacklight()->SetBrightness(0); + gpio_set_level(PWR_Control_PIN, false); + } + else { + self->GetBacklight()->RestoreBrightness(); + gpio_set_level(PWR_Control_PIN, true); + } + }, this); + } + +public: + CustomBoard() { + InitializeI2c(); + InitializeTca9554(); + InitializeSpi(); + InitializeSpd2010Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, I2S_STD_SLOT_LEFT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN, I2S_STD_SLOT_RIGHT); // I2S_STD_SLOT_LEFT / I2S_STD_SLOT_RIGHT / I2S_STD_SLOT_BOTH + + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(CustomBoard); + +CustomBoard* CustomBoard::instance_ = nullptr; diff --git a/main/boards/esp32-s3-touch-lcd-1.85/README.md b/main/boards/esp32-s3-touch-lcd-1.85/README.md new file mode 100644 index 0000000..df8a905 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-1.85 +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-1.85.htm \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.85/config.h b/main/boards/esp32-s3-touch-lcd-1.85/config.h new file mode 100644 index 0000000..7eff4c6 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85/config.h @@ -0,0 +1,69 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_6 +#define PWR_Control_PIN GPIO_NUM_7 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_2 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_15 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_47 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_48 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_38 + +#define I2C_SCL_IO GPIO_NUM_10 +#define I2C_SDA_IO GPIO_NUM_11 + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 + +#define DISPLAY_WIDTH 360 +#define DISPLAY_HEIGHT 360 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define QSPI_LCD_H_RES (360) +#define QSPI_LCD_V_RES (360) +#define QSPI_LCD_BIT_PER_PIXEL (16) + +#define QSPI_LCD_HOST SPI2_HOST +#define QSPI_PIN_NUM_LCD_PCLK GPIO_NUM_40 +#define QSPI_PIN_NUM_LCD_CS GPIO_NUM_21 +#define QSPI_PIN_NUM_LCD_DATA0 GPIO_NUM_46 +#define QSPI_PIN_NUM_LCD_DATA1 GPIO_NUM_45 +#define QSPI_PIN_NUM_LCD_DATA2 GPIO_NUM_42 +#define QSPI_PIN_NUM_LCD_DATA3 GPIO_NUM_41 +#define QSPI_PIN_NUM_LCD_RST GPIO_NUM_NC +#define QSPI_PIN_NUM_LCD_BL GPIO_NUM_5 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define TP_PORT (I2C_NUM_1) +#define TP_PIN_NUM_SDA (GPIO_NUM_1) +#define TP_PIN_NUM_SCL (GPIO_NUM_3) +#define TP_PIN_NUM_RST (GPIO_NUM_NC) +#define TP_PIN_NUM_INT (GPIO_NUM_4) + +#define DISPLAY_BACKLIGHT_PIN QSPI_PIN_NUM_LCD_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(sclk, d0, d1, d2, d3, max_trans_sz) \ + { \ + .data0_io_num = d0, \ + .data1_io_num = d1, \ + .sclk_io_num = sclk, \ + .data2_io_num = d2, \ + .data3_io_num = d3, \ + .max_transfer_sz = max_trans_sz, \ + } + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-s3-touch-lcd-1.85/config.json b/main/boards/esp32-s3-touch-lcd-1.85/config.json new file mode 100644 index 0000000..63207b5 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32-s3-touch-lcd-1.85", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.85/esp32-s3-touch-lcd-1.85.cc b/main/boards/esp32-s3-touch-lcd-1.85/esp32-s3-touch-lcd-1.85.cc new file mode 100644 index 0000000..ecdc7a3 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85/esp32-s3-touch-lcd-1.85.cc @@ -0,0 +1,447 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" + +#define TAG "waveshare_lcd_1_85" + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x0BULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const st77916_lcd_init_cmd_t vendor_specific_init_new[] = { + {0xF0, (uint8_t []){0x28}, 1, 0}, + {0xF2, (uint8_t []){0x28}, 1, 0}, + {0x73, (uint8_t []){0xF0}, 1, 0}, + {0x7C, (uint8_t []){0xD1}, 1, 0}, + {0x83, (uint8_t []){0xE0}, 1, 0}, + {0x84, (uint8_t []){0x61}, 1, 0}, + {0xF2, (uint8_t []){0x82}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x01}, 1, 0}, + {0xF1, (uint8_t []){0x01}, 1, 0}, + {0xB0, (uint8_t []){0x56}, 1, 0}, + {0xB1, (uint8_t []){0x4D}, 1, 0}, + {0xB2, (uint8_t []){0x24}, 1, 0}, + {0xB4, (uint8_t []){0x87}, 1, 0}, + {0xB5, (uint8_t []){0x44}, 1, 0}, + {0xB6, (uint8_t []){0x8B}, 1, 0}, + {0xB7, (uint8_t []){0x40}, 1, 0}, + {0xB8, (uint8_t []){0x86}, 1, 0}, + {0xBA, (uint8_t []){0x00}, 1, 0}, + {0xBB, (uint8_t []){0x08}, 1, 0}, + {0xBC, (uint8_t []){0x08}, 1, 0}, + {0xBD, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x80}, 1, 0}, + {0xC1, (uint8_t []){0x10}, 1, 0}, + {0xC2, (uint8_t []){0x37}, 1, 0}, + {0xC3, (uint8_t []){0x80}, 1, 0}, + {0xC4, (uint8_t []){0x10}, 1, 0}, + {0xC5, (uint8_t []){0x37}, 1, 0}, + {0xC6, (uint8_t []){0xA9}, 1, 0}, + {0xC7, (uint8_t []){0x41}, 1, 0}, + {0xC8, (uint8_t []){0x01}, 1, 0}, + {0xC9, (uint8_t []){0xA9}, 1, 0}, + {0xCA, (uint8_t []){0x41}, 1, 0}, + {0xCB, (uint8_t []){0x01}, 1, 0}, + {0xD0, (uint8_t []){0x91}, 1, 0}, + {0xD1, (uint8_t []){0x68}, 1, 0}, + {0xD2, (uint8_t []){0x68}, 1, 0}, + {0xF5, (uint8_t []){0x00, 0xA5}, 2, 0}, + {0xDD, (uint8_t []){0x4F}, 1, 0}, + {0xDE, (uint8_t []){0x4F}, 1, 0}, + {0xF1, (uint8_t []){0x10}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0xF0, 0x0A, 0x10, 0x09, 0x09, 0x36, 0x35, 0x33, 0x4A, 0x29, 0x15, 0x15, 0x2E, 0x34}, 14, 0}, + {0xE1, (uint8_t []){0xF0, 0x0A, 0x0F, 0x08, 0x08, 0x05, 0x34, 0x33, 0x4A, 0x39, 0x15, 0x15, 0x2D, 0x33}, 14, 0}, + {0xF0, (uint8_t []){0x10}, 1, 0}, + {0xF3, (uint8_t []){0x10}, 1, 0}, + {0xE0, (uint8_t []){0x07}, 1, 0}, + {0xE1, (uint8_t []){0x00}, 1, 0}, + {0xE2, (uint8_t []){0x00}, 1, 0}, + {0xE3, (uint8_t []){0x00}, 1, 0}, + {0xE4, (uint8_t []){0xE0}, 1, 0}, + {0xE5, (uint8_t []){0x06}, 1, 0}, + {0xE6, (uint8_t []){0x21}, 1, 0}, + {0xE7, (uint8_t []){0x01}, 1, 0}, + {0xE8, (uint8_t []){0x05}, 1, 0}, + {0xE9, (uint8_t []){0x02}, 1, 0}, + {0xEA, (uint8_t []){0xDA}, 1, 0}, + {0xEB, (uint8_t []){0x00}, 1, 0}, + {0xEC, (uint8_t []){0x00}, 1, 0}, + {0xED, (uint8_t []){0x0F}, 1, 0}, + {0xEE, (uint8_t []){0x00}, 1, 0}, + {0xEF, (uint8_t []){0x00}, 1, 0}, + {0xF8, (uint8_t []){0x00}, 1, 0}, + {0xF9, (uint8_t []){0x00}, 1, 0}, + {0xFA, (uint8_t []){0x00}, 1, 0}, + {0xFB, (uint8_t []){0x00}, 1, 0}, + {0xFC, (uint8_t []){0x00}, 1, 0}, + {0xFD, (uint8_t []){0x00}, 1, 0}, + {0xFE, (uint8_t []){0x00}, 1, 0}, + {0xFF, (uint8_t []){0x00}, 1, 0}, + {0x60, (uint8_t []){0x40}, 1, 0}, + {0x61, (uint8_t []){0x04}, 1, 0}, + {0x62, (uint8_t []){0x00}, 1, 0}, + {0x63, (uint8_t []){0x42}, 1, 0}, + {0x64, (uint8_t []){0xD9}, 1, 0}, + {0x65, (uint8_t []){0x00}, 1, 0}, + {0x66, (uint8_t []){0x00}, 1, 0}, + {0x67, (uint8_t []){0x00}, 1, 0}, + {0x68, (uint8_t []){0x00}, 1, 0}, + {0x69, (uint8_t []){0x00}, 1, 0}, + {0x6A, (uint8_t []){0x00}, 1, 0}, + {0x6B, (uint8_t []){0x00}, 1, 0}, + {0x70, (uint8_t []){0x40}, 1, 0}, + {0x71, (uint8_t []){0x03}, 1, 0}, + {0x72, (uint8_t []){0x00}, 1, 0}, + {0x73, (uint8_t []){0x42}, 1, 0}, + {0x74, (uint8_t []){0xD8}, 1, 0}, + {0x75, (uint8_t []){0x00}, 1, 0}, + {0x76, (uint8_t []){0x00}, 1, 0}, + {0x77, (uint8_t []){0x00}, 1, 0}, + {0x78, (uint8_t []){0x00}, 1, 0}, + {0x79, (uint8_t []){0x00}, 1, 0}, + {0x7A, (uint8_t []){0x00}, 1, 0}, + {0x7B, (uint8_t []){0x00}, 1, 0}, + {0x80, (uint8_t []){0x48}, 1, 0}, + {0x81, (uint8_t []){0x00}, 1, 0}, + {0x82, (uint8_t []){0x06}, 1, 0}, + {0x83, (uint8_t []){0x02}, 1, 0}, + {0x84, (uint8_t []){0xD6}, 1, 0}, + {0x85, (uint8_t []){0x04}, 1, 0}, + {0x86, (uint8_t []){0x00}, 1, 0}, + {0x87, (uint8_t []){0x00}, 1, 0}, + {0x88, (uint8_t []){0x48}, 1, 0}, + {0x89, (uint8_t []){0x00}, 1, 0}, + {0x8A, (uint8_t []){0x08}, 1, 0}, + {0x8B, (uint8_t []){0x02}, 1, 0}, + {0x8C, (uint8_t []){0xD8}, 1, 0}, + {0x8D, (uint8_t []){0x04}, 1, 0}, + {0x8E, (uint8_t []){0x00}, 1, 0}, + {0x8F, (uint8_t []){0x00}, 1, 0}, + {0x90, (uint8_t []){0x48}, 1, 0}, + {0x91, (uint8_t []){0x00}, 1, 0}, + {0x92, (uint8_t []){0x0A}, 1, 0}, + {0x93, (uint8_t []){0x02}, 1, 0}, + {0x94, (uint8_t []){0xDA}, 1, 0}, + {0x95, (uint8_t []){0x04}, 1, 0}, + {0x96, (uint8_t []){0x00}, 1, 0}, + {0x97, (uint8_t []){0x00}, 1, 0}, + {0x98, (uint8_t []){0x48}, 1, 0}, + {0x99, (uint8_t []){0x00}, 1, 0}, + {0x9A, (uint8_t []){0x0C}, 1, 0}, + {0x9B, (uint8_t []){0x02}, 1, 0}, + {0x9C, (uint8_t []){0xDC}, 1, 0}, + {0x9D, (uint8_t []){0x04}, 1, 0}, + {0x9E, (uint8_t []){0x00}, 1, 0}, + {0x9F, (uint8_t []){0x00}, 1, 0}, + {0xA0, (uint8_t []){0x48}, 1, 0}, + {0xA1, (uint8_t []){0x00}, 1, 0}, + {0xA2, (uint8_t []){0x05}, 1, 0}, + {0xA3, (uint8_t []){0x02}, 1, 0}, + {0xA4, (uint8_t []){0xD5}, 1, 0}, + {0xA5, (uint8_t []){0x04}, 1, 0}, + {0xA6, (uint8_t []){0x00}, 1, 0}, + {0xA7, (uint8_t []){0x00}, 1, 0}, + {0xA8, (uint8_t []){0x48}, 1, 0}, + {0xA9, (uint8_t []){0x00}, 1, 0}, + {0xAA, (uint8_t []){0x07}, 1, 0}, + {0xAB, (uint8_t []){0x02}, 1, 0}, + {0xAC, (uint8_t []){0xD7}, 1, 0}, + {0xAD, (uint8_t []){0x04}, 1, 0}, + {0xAE, (uint8_t []){0x00}, 1, 0}, + {0xAF, (uint8_t []){0x00}, 1, 0}, + {0xB0, (uint8_t []){0x48}, 1, 0}, + {0xB1, (uint8_t []){0x00}, 1, 0}, + {0xB2, (uint8_t []){0x09}, 1, 0}, + {0xB3, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0xD9}, 1, 0}, + {0xB5, (uint8_t []){0x04}, 1, 0}, + {0xB6, (uint8_t []){0x00}, 1, 0}, + {0xB7, (uint8_t []){0x00}, 1, 0}, + + {0xB8, (uint8_t []){0x48}, 1, 0}, + {0xB9, (uint8_t []){0x00}, 1, 0}, + {0xBA, (uint8_t []){0x0B}, 1, 0}, + {0xBB, (uint8_t []){0x02}, 1, 0}, + {0xBC, (uint8_t []){0xDB}, 1, 0}, + {0xBD, (uint8_t []){0x04}, 1, 0}, + {0xBE, (uint8_t []){0x00}, 1, 0}, + {0xBF, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x10}, 1, 0}, + {0xC1, (uint8_t []){0x47}, 1, 0}, + {0xC2, (uint8_t []){0x56}, 1, 0}, + {0xC3, (uint8_t []){0x65}, 1, 0}, + {0xC4, (uint8_t []){0x74}, 1, 0}, + {0xC5, (uint8_t []){0x88}, 1, 0}, + {0xC6, (uint8_t []){0x99}, 1, 0}, + {0xC7, (uint8_t []){0x01}, 1, 0}, + {0xC8, (uint8_t []){0xBB}, 1, 0}, + {0xC9, (uint8_t []){0xAA}, 1, 0}, + {0xD0, (uint8_t []){0x10}, 1, 0}, + {0xD1, (uint8_t []){0x47}, 1, 0}, + {0xD2, (uint8_t []){0x56}, 1, 0}, + {0xD3, (uint8_t []){0x65}, 1, 0}, + {0xD4, (uint8_t []){0x74}, 1, 0}, + {0xD5, (uint8_t []){0x88}, 1, 0}, + {0xD6, (uint8_t []){0x99}, 1, 0}, + {0xD7, (uint8_t []){0x01}, 1, 0}, + {0xD8, (uint8_t []){0xBB}, 1, 0}, + {0xD9, (uint8_t []){0xAA}, 1, 0}, + {0xF3, (uint8_t []){0x01}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0x21, (uint8_t []){0x00}, 1, 0}, + {0x11, (uint8_t []){0x00}, 1, 120}, + {0x29, (uint8_t []){0x00}, 1, 0}, +}; +class CustomBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + button_handle_t boot_btn, pwr_btn; + button_driver_t* boot_btn_driver_ = nullptr; + button_driver_t* pwr_btn_driver_ = nullptr; + static CustomBoard* instance_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = I2C_SDA_IO, + .scl_io_num = I2C_SCL_IO, + .clk_source = I2C_CLK_SRC_DEFAULT, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + + // uint32_t input_level_mask = 0; + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_INPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输入 + // ret = esp_io_expander_get_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, &input_level_mask); // 获取引脚 EXIO0 和 EXIO1 的电平状态,存放在 input_level_mask 中 + + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO2 和 EXIO3 模式为输出 + // ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, 1); // 将引脚电平设置为 1 + // ret = esp_io_expander_print_state(io_expander); // 打印引脚状态 + + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输出 + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + + const spi_bus_config_t bus_config = TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(QSPI_PIN_NUM_LCD_PCLK, + QSPI_PIN_NUM_LCD_DATA0, + QSPI_PIN_NUM_LCD_DATA1, + QSPI_PIN_NUM_LCD_DATA2, + QSPI_PIN_NUM_LCD_DATA3, + QSPI_LCD_H_RES * 80 * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(QSPI_LCD_HOST, &bus_config, SPI_DMA_CH_AUTO)); + } + + void Initializest77916Display() { + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGI(TAG, "Install panel IO"); + + esp_lcd_panel_io_spi_config_t io_config = { + .cs_gpio_num = QSPI_PIN_NUM_LCD_CS, + .dc_gpio_num = -1, + .spi_mode = 0, + .pclk_hz = 3 * 1000 * 1000, + .trans_queue_depth = 10, + .on_color_trans_done = NULL, + .user_ctx = NULL, + .lcd_cmd_bits = 32, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .octal_mode = 0, + .quad_mode = 1, + .sio_mode = 0, + .lsb_first = 0, + .cs_high_active = 0, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io)); + + ESP_LOGI(TAG, "Install ST77916 panel driver"); + + st77916_vendor_config_t vendor_config = { + .flags = { + .use_qspi_interface = 1, + }, + }; + + printf("-------------------------------------- Version selection -------------------------------------- \r\n"); + esp_err_t ret; + int lcd_cmd = 0x04; + uint8_t register_data[4]; + size_t param_size = sizeof(register_data); + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_READ_CMD << 24; // Use the read opcode instead of write + ret = esp_lcd_panel_io_rx_param(panel_io, lcd_cmd, register_data, param_size); + if (ret == ESP_OK) { + printf("Register 0x04 data: %02x %02x %02x %02x\n", register_data[0], register_data[1], register_data[2], register_data[3]); + } else { + printf("Failed to read register 0x04, error code: %d\n", ret); + } + // panel_io_spi_del(io_handle); + io_config.pclk_hz = 80 * 1000 * 1000; + if (esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io) != ESP_OK){ + printf("Failed to set LCD communication parameters -- SPI\r\n"); + return ; + } + printf("LCD communication parameters are set successfully -- SPI\r\n"); + + // Check register values and configure accordingly + if (register_data[0] == 0x00 && register_data[1] == 0x7F && register_data[2] == 0x7F && register_data[3] == 0x7F) { + // Handle the case where the register data matches this pattern + printf("Vendor-specific initialization for case 1.\n"); + } + else if (register_data[0] == 0x00 && register_data[1] == 0x02 && register_data[2] == 0x7F && register_data[3] == 0x7F) { + // Provide vendor-specific initialization commands if register data matches this pattern + vendor_config.init_cmds = vendor_specific_init_new; + vendor_config.init_cmds_size = sizeof(vendor_specific_init_new) / sizeof(st77916_lcd_init_cmd_t); + printf("Vendor-specific initialization for case 2.\n"); + } + printf("------------------------------------- End of version selection------------------------------------- \r\n"); + + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = QSPI_PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, // Implemented by LCD command `36h` + .bits_per_pixel = QSPI_LCD_BIT_PER_PIXEL, // Implemented by LCD command `3Ah` (16/18) + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st77916(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_disp_on_off(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtonsCustom() { + gpio_reset_pin(BOOT_BUTTON_GPIO); + gpio_set_direction(BOOT_BUTTON_GPIO, GPIO_MODE_INPUT); + gpio_reset_pin(PWR_BUTTON_GPIO); + gpio_set_direction(PWR_BUTTON_GPIO, GPIO_MODE_INPUT); + gpio_reset_pin(PWR_Control_PIN); + gpio_set_direction(PWR_Control_PIN, GPIO_MODE_OUTPUT); + // gpio_set_level(PWR_Control_PIN, false); + gpio_set_level(PWR_Control_PIN, true); + } + void InitializeButtons() { + instance_ = this; + InitializeButtonsCustom(); + + // Boot Button + button_config_t boot_btn_config = { + .long_press_time = 2000, + .short_press_time = 0 + }; + boot_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + boot_btn_driver_->enable_power_save = false; + boot_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !gpio_get_level(BOOT_BUTTON_GPIO); + }; + ESP_ERROR_CHECK(iot_button_create(&boot_btn_config, boot_btn_driver_, &boot_btn)); + iot_button_register_cb(boot_btn, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + app.ToggleChatState(); + }, this); + + // Power Button + button_config_t pwr_btn_config = { + .long_press_time = 5000, + .short_press_time = 0 + }; + pwr_btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + pwr_btn_driver_->enable_power_save = false; + pwr_btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !gpio_get_level(PWR_BUTTON_GPIO); + }; + ESP_ERROR_CHECK(iot_button_create(&pwr_btn_config, pwr_btn_driver_, &pwr_btn)); + iot_button_register_cb(pwr_btn, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + if(self->GetBacklight()->brightness() > 0) { + self->GetBacklight()->SetBrightness(0); + gpio_set_level(PWR_Control_PIN, false); + } + else { + self->GetBacklight()->RestoreBrightness(); + gpio_set_level(PWR_Control_PIN, true); + } + }, this); + } + +public: + CustomBoard() { + InitializeI2c(); + InitializeTca9554(); + InitializeSpi(); + Initializest77916Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, I2S_STD_SLOT_BOTH, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN, I2S_STD_SLOT_RIGHT); // I2S_STD_SLOT_LEFT / I2S_STD_SLOT_RIGHT / I2S_STD_SLOT_BOTH + + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(CustomBoard); + +CustomBoard* CustomBoard::instance_ = nullptr; diff --git a/main/boards/esp32-s3-touch-lcd-1.85c/README.md b/main/boards/esp32-s3-touch-lcd-1.85c/README.md new file mode 100644 index 0000000..7668dec --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85c/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-1.85C +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-1.85C.htm \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.85c/config.h b/main/boards/esp32-s3-touch-lcd-1.85c/config.h new file mode 100644 index 0000000..dfd5a89 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85c/config.h @@ -0,0 +1,67 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_2 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_15 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_47 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_48 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_38 + +#define I2C_SCL_IO GPIO_NUM_10 +#define I2C_SDA_IO GPIO_NUM_11 + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 + +#define DISPLAY_WIDTH 360 +#define DISPLAY_HEIGHT 360 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define QSPI_LCD_H_RES (360) +#define QSPI_LCD_V_RES (360) +#define QSPI_LCD_BIT_PER_PIXEL (16) + +#define QSPI_LCD_HOST SPI2_HOST +#define QSPI_PIN_NUM_LCD_PCLK GPIO_NUM_40 +#define QSPI_PIN_NUM_LCD_CS GPIO_NUM_21 +#define QSPI_PIN_NUM_LCD_DATA0 GPIO_NUM_46 +#define QSPI_PIN_NUM_LCD_DATA1 GPIO_NUM_45 +#define QSPI_PIN_NUM_LCD_DATA2 GPIO_NUM_42 +#define QSPI_PIN_NUM_LCD_DATA3 GPIO_NUM_41 +#define QSPI_PIN_NUM_LCD_RST GPIO_NUM_NC +#define QSPI_PIN_NUM_LCD_BL GPIO_NUM_5 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define TP_PORT (I2C_NUM_1) +#define TP_PIN_NUM_SDA (I2C_SDA_IO) +#define TP_PIN_NUM_SCL (I2C_SCL_IO) +#define TP_PIN_NUM_RST (GPIO_NUM_NC) +#define TP_PIN_NUM_INT (GPIO_NUM_4) + +#define DISPLAY_BACKLIGHT_PIN QSPI_PIN_NUM_LCD_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(sclk, d0, d1, d2, d3, max_trans_sz) \ + { \ + .data0_io_num = d0, \ + .data1_io_num = d1, \ + .sclk_io_num = sclk, \ + .data2_io_num = d2, \ + .data3_io_num = d3, \ + .max_transfer_sz = max_trans_sz, \ + } + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-s3-touch-lcd-1.85c/config.json b/main/boards/esp32-s3-touch-lcd-1.85c/config.json new file mode 100644 index 0000000..1832799 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85c/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32-s3-touch-lcd-1.85c", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-1.85c/esp32-s3-touch-lcd-1.85c.cc b/main/boards/esp32-s3-touch-lcd-1.85c/esp32-s3-touch-lcd-1.85c.cc new file mode 100644 index 0000000..cf5c172 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-1.85c/esp32-s3-touch-lcd-1.85c.cc @@ -0,0 +1,396 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" + +#define TAG "waveshare_lcd_1_85c" + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x0BULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const st77916_lcd_init_cmd_t vendor_specific_init_new[] = { + {0xF0, (uint8_t []){0x28}, 1, 0}, + {0xF2, (uint8_t []){0x28}, 1, 0}, + {0x73, (uint8_t []){0xF0}, 1, 0}, + {0x7C, (uint8_t []){0xD1}, 1, 0}, + {0x83, (uint8_t []){0xE0}, 1, 0}, + {0x84, (uint8_t []){0x61}, 1, 0}, + {0xF2, (uint8_t []){0x82}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x01}, 1, 0}, + {0xF1, (uint8_t []){0x01}, 1, 0}, + {0xB0, (uint8_t []){0x56}, 1, 0}, + {0xB1, (uint8_t []){0x4D}, 1, 0}, + {0xB2, (uint8_t []){0x24}, 1, 0}, + {0xB4, (uint8_t []){0x87}, 1, 0}, + {0xB5, (uint8_t []){0x44}, 1, 0}, + {0xB6, (uint8_t []){0x8B}, 1, 0}, + {0xB7, (uint8_t []){0x40}, 1, 0}, + {0xB8, (uint8_t []){0x86}, 1, 0}, + {0xBA, (uint8_t []){0x00}, 1, 0}, + {0xBB, (uint8_t []){0x08}, 1, 0}, + {0xBC, (uint8_t []){0x08}, 1, 0}, + {0xBD, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x80}, 1, 0}, + {0xC1, (uint8_t []){0x10}, 1, 0}, + {0xC2, (uint8_t []){0x37}, 1, 0}, + {0xC3, (uint8_t []){0x80}, 1, 0}, + {0xC4, (uint8_t []){0x10}, 1, 0}, + {0xC5, (uint8_t []){0x37}, 1, 0}, + {0xC6, (uint8_t []){0xA9}, 1, 0}, + {0xC7, (uint8_t []){0x41}, 1, 0}, + {0xC8, (uint8_t []){0x01}, 1, 0}, + {0xC9, (uint8_t []){0xA9}, 1, 0}, + {0xCA, (uint8_t []){0x41}, 1, 0}, + {0xCB, (uint8_t []){0x01}, 1, 0}, + {0xD0, (uint8_t []){0x91}, 1, 0}, + {0xD1, (uint8_t []){0x68}, 1, 0}, + {0xD2, (uint8_t []){0x68}, 1, 0}, + {0xF5, (uint8_t []){0x00, 0xA5}, 2, 0}, + {0xDD, (uint8_t []){0x4F}, 1, 0}, + {0xDE, (uint8_t []){0x4F}, 1, 0}, + {0xF1, (uint8_t []){0x10}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0xF0, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0xF0, 0x0A, 0x10, 0x09, 0x09, 0x36, 0x35, 0x33, 0x4A, 0x29, 0x15, 0x15, 0x2E, 0x34}, 14, 0}, + {0xE1, (uint8_t []){0xF0, 0x0A, 0x0F, 0x08, 0x08, 0x05, 0x34, 0x33, 0x4A, 0x39, 0x15, 0x15, 0x2D, 0x33}, 14, 0}, + {0xF0, (uint8_t []){0x10}, 1, 0}, + {0xF3, (uint8_t []){0x10}, 1, 0}, + {0xE0, (uint8_t []){0x07}, 1, 0}, + {0xE1, (uint8_t []){0x00}, 1, 0}, + {0xE2, (uint8_t []){0x00}, 1, 0}, + {0xE3, (uint8_t []){0x00}, 1, 0}, + {0xE4, (uint8_t []){0xE0}, 1, 0}, + {0xE5, (uint8_t []){0x06}, 1, 0}, + {0xE6, (uint8_t []){0x21}, 1, 0}, + {0xE7, (uint8_t []){0x01}, 1, 0}, + {0xE8, (uint8_t []){0x05}, 1, 0}, + {0xE9, (uint8_t []){0x02}, 1, 0}, + {0xEA, (uint8_t []){0xDA}, 1, 0}, + {0xEB, (uint8_t []){0x00}, 1, 0}, + {0xEC, (uint8_t []){0x00}, 1, 0}, + {0xED, (uint8_t []){0x0F}, 1, 0}, + {0xEE, (uint8_t []){0x00}, 1, 0}, + {0xEF, (uint8_t []){0x00}, 1, 0}, + {0xF8, (uint8_t []){0x00}, 1, 0}, + {0xF9, (uint8_t []){0x00}, 1, 0}, + {0xFA, (uint8_t []){0x00}, 1, 0}, + {0xFB, (uint8_t []){0x00}, 1, 0}, + {0xFC, (uint8_t []){0x00}, 1, 0}, + {0xFD, (uint8_t []){0x00}, 1, 0}, + {0xFE, (uint8_t []){0x00}, 1, 0}, + {0xFF, (uint8_t []){0x00}, 1, 0}, + {0x60, (uint8_t []){0x40}, 1, 0}, + {0x61, (uint8_t []){0x04}, 1, 0}, + {0x62, (uint8_t []){0x00}, 1, 0}, + {0x63, (uint8_t []){0x42}, 1, 0}, + {0x64, (uint8_t []){0xD9}, 1, 0}, + {0x65, (uint8_t []){0x00}, 1, 0}, + {0x66, (uint8_t []){0x00}, 1, 0}, + {0x67, (uint8_t []){0x00}, 1, 0}, + {0x68, (uint8_t []){0x00}, 1, 0}, + {0x69, (uint8_t []){0x00}, 1, 0}, + {0x6A, (uint8_t []){0x00}, 1, 0}, + {0x6B, (uint8_t []){0x00}, 1, 0}, + {0x70, (uint8_t []){0x40}, 1, 0}, + {0x71, (uint8_t []){0x03}, 1, 0}, + {0x72, (uint8_t []){0x00}, 1, 0}, + {0x73, (uint8_t []){0x42}, 1, 0}, + {0x74, (uint8_t []){0xD8}, 1, 0}, + {0x75, (uint8_t []){0x00}, 1, 0}, + {0x76, (uint8_t []){0x00}, 1, 0}, + {0x77, (uint8_t []){0x00}, 1, 0}, + {0x78, (uint8_t []){0x00}, 1, 0}, + {0x79, (uint8_t []){0x00}, 1, 0}, + {0x7A, (uint8_t []){0x00}, 1, 0}, + {0x7B, (uint8_t []){0x00}, 1, 0}, + {0x80, (uint8_t []){0x48}, 1, 0}, + {0x81, (uint8_t []){0x00}, 1, 0}, + {0x82, (uint8_t []){0x06}, 1, 0}, + {0x83, (uint8_t []){0x02}, 1, 0}, + {0x84, (uint8_t []){0xD6}, 1, 0}, + {0x85, (uint8_t []){0x04}, 1, 0}, + {0x86, (uint8_t []){0x00}, 1, 0}, + {0x87, (uint8_t []){0x00}, 1, 0}, + {0x88, (uint8_t []){0x48}, 1, 0}, + {0x89, (uint8_t []){0x00}, 1, 0}, + {0x8A, (uint8_t []){0x08}, 1, 0}, + {0x8B, (uint8_t []){0x02}, 1, 0}, + {0x8C, (uint8_t []){0xD8}, 1, 0}, + {0x8D, (uint8_t []){0x04}, 1, 0}, + {0x8E, (uint8_t []){0x00}, 1, 0}, + {0x8F, (uint8_t []){0x00}, 1, 0}, + {0x90, (uint8_t []){0x48}, 1, 0}, + {0x91, (uint8_t []){0x00}, 1, 0}, + {0x92, (uint8_t []){0x0A}, 1, 0}, + {0x93, (uint8_t []){0x02}, 1, 0}, + {0x94, (uint8_t []){0xDA}, 1, 0}, + {0x95, (uint8_t []){0x04}, 1, 0}, + {0x96, (uint8_t []){0x00}, 1, 0}, + {0x97, (uint8_t []){0x00}, 1, 0}, + {0x98, (uint8_t []){0x48}, 1, 0}, + {0x99, (uint8_t []){0x00}, 1, 0}, + {0x9A, (uint8_t []){0x0C}, 1, 0}, + {0x9B, (uint8_t []){0x02}, 1, 0}, + {0x9C, (uint8_t []){0xDC}, 1, 0}, + {0x9D, (uint8_t []){0x04}, 1, 0}, + {0x9E, (uint8_t []){0x00}, 1, 0}, + {0x9F, (uint8_t []){0x00}, 1, 0}, + {0xA0, (uint8_t []){0x48}, 1, 0}, + {0xA1, (uint8_t []){0x00}, 1, 0}, + {0xA2, (uint8_t []){0x05}, 1, 0}, + {0xA3, (uint8_t []){0x02}, 1, 0}, + {0xA4, (uint8_t []){0xD5}, 1, 0}, + {0xA5, (uint8_t []){0x04}, 1, 0}, + {0xA6, (uint8_t []){0x00}, 1, 0}, + {0xA7, (uint8_t []){0x00}, 1, 0}, + {0xA8, (uint8_t []){0x48}, 1, 0}, + {0xA9, (uint8_t []){0x00}, 1, 0}, + {0xAA, (uint8_t []){0x07}, 1, 0}, + {0xAB, (uint8_t []){0x02}, 1, 0}, + {0xAC, (uint8_t []){0xD7}, 1, 0}, + {0xAD, (uint8_t []){0x04}, 1, 0}, + {0xAE, (uint8_t []){0x00}, 1, 0}, + {0xAF, (uint8_t []){0x00}, 1, 0}, + {0xB0, (uint8_t []){0x48}, 1, 0}, + {0xB1, (uint8_t []){0x00}, 1, 0}, + {0xB2, (uint8_t []){0x09}, 1, 0}, + {0xB3, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0xD9}, 1, 0}, + {0xB5, (uint8_t []){0x04}, 1, 0}, + {0xB6, (uint8_t []){0x00}, 1, 0}, + {0xB7, (uint8_t []){0x00}, 1, 0}, + + {0xB8, (uint8_t []){0x48}, 1, 0}, + {0xB9, (uint8_t []){0x00}, 1, 0}, + {0xBA, (uint8_t []){0x0B}, 1, 0}, + {0xBB, (uint8_t []){0x02}, 1, 0}, + {0xBC, (uint8_t []){0xDB}, 1, 0}, + {0xBD, (uint8_t []){0x04}, 1, 0}, + {0xBE, (uint8_t []){0x00}, 1, 0}, + {0xBF, (uint8_t []){0x00}, 1, 0}, + {0xC0, (uint8_t []){0x10}, 1, 0}, + {0xC1, (uint8_t []){0x47}, 1, 0}, + {0xC2, (uint8_t []){0x56}, 1, 0}, + {0xC3, (uint8_t []){0x65}, 1, 0}, + {0xC4, (uint8_t []){0x74}, 1, 0}, + {0xC5, (uint8_t []){0x88}, 1, 0}, + {0xC6, (uint8_t []){0x99}, 1, 0}, + {0xC7, (uint8_t []){0x01}, 1, 0}, + {0xC8, (uint8_t []){0xBB}, 1, 0}, + {0xC9, (uint8_t []){0xAA}, 1, 0}, + {0xD0, (uint8_t []){0x10}, 1, 0}, + {0xD1, (uint8_t []){0x47}, 1, 0}, + {0xD2, (uint8_t []){0x56}, 1, 0}, + {0xD3, (uint8_t []){0x65}, 1, 0}, + {0xD4, (uint8_t []){0x74}, 1, 0}, + {0xD5, (uint8_t []){0x88}, 1, 0}, + {0xD6, (uint8_t []){0x99}, 1, 0}, + {0xD7, (uint8_t []){0x01}, 1, 0}, + {0xD8, (uint8_t []){0xBB}, 1, 0}, + {0xD9, (uint8_t []){0xAA}, 1, 0}, + {0xF3, (uint8_t []){0x01}, 1, 0}, + {0xF0, (uint8_t []){0x00}, 1, 0}, + {0x21, (uint8_t []){0x00}, 1, 0}, + {0x11, (uint8_t []){0x00}, 1, 120}, + {0x29, (uint8_t []){0x00}, 1, 0}, +}; + +class CustomBoard : public WifiBoard { +private: + Button boot_button_; + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = I2C_SDA_IO, + .scl_io_num = I2C_SCL_IO, + .clk_source = I2C_CLK_SRC_DEFAULT, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) + { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + + // uint32_t input_level_mask = 0; + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_INPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输入 + // ret = esp_io_expander_get_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, &input_level_mask); // 获取引脚 EXIO0 和 EXIO1 的电平状态,存放在 input_level_mask 中 + + // ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO2 和 EXIO3 模式为输出 + // ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, 1); // 将引脚电平设置为 1 + // ret = esp_io_expander_print_state(io_expander); // 打印引脚状态 + + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输出 + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(300)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + + const spi_bus_config_t bus_config = TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(QSPI_PIN_NUM_LCD_PCLK, + QSPI_PIN_NUM_LCD_DATA0, + QSPI_PIN_NUM_LCD_DATA1, + QSPI_PIN_NUM_LCD_DATA2, + QSPI_PIN_NUM_LCD_DATA3, + QSPI_LCD_H_RES * 80 * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(QSPI_LCD_HOST, &bus_config, SPI_DMA_CH_AUTO)); + } + + void Initializest77916Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGI(TAG, "Install panel IO"); + + esp_lcd_panel_io_spi_config_t io_config = { + .cs_gpio_num = QSPI_PIN_NUM_LCD_CS, + .dc_gpio_num = -1, + .spi_mode = 0, + .pclk_hz = 3 * 1000 * 1000, + .trans_queue_depth = 10, + .on_color_trans_done = NULL, + .user_ctx = NULL, + .lcd_cmd_bits = 32, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .octal_mode = 0, + .quad_mode = 1, + .sio_mode = 0, + .lsb_first = 0, + .cs_high_active = 0, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io)); + + ESP_LOGI(TAG, "Install ST77916 panel driver"); + + st77916_vendor_config_t vendor_config = { + .flags = { + .use_qspi_interface = 1, + }, + }; + + printf("-------------------------------------- Version selection -------------------------------------- \r\n"); + esp_err_t ret; + int lcd_cmd = 0x04; + uint8_t register_data[4]; + size_t param_size = sizeof(register_data); + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_READ_CMD << 24; // Use the read opcode instead of write + ret = esp_lcd_panel_io_rx_param(panel_io, lcd_cmd, register_data, param_size); + if (ret == ESP_OK) { + printf("Register 0x04 data: %02x %02x %02x %02x\n", register_data[0], register_data[1], register_data[2], register_data[3]); + } else { + printf("Failed to read register 0x04, error code: %d\n", ret); + } + // panel_io_spi_del(io_handle); + io_config.pclk_hz = 80 * 1000 * 1000; + if (esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io) != ESP_OK) { + printf("Failed to set LCD communication parameters -- SPI\r\n"); + return ; + } + printf("LCD communication parameters are set successfully -- SPI\r\n"); + + // Check register values and configure accordingly + if (register_data[0] == 0x00 && register_data[1] == 0x7F && register_data[2] == 0x7F && register_data[3] == 0x7F) { + // Handle the case where the register data matches this pattern + printf("Vendor-specific initialization for case 1.\n"); + } + else if (register_data[0] == 0x00 && register_data[1] == 0x02 && register_data[2] == 0x7F && register_data[3] == 0x7F) { + // Provide vendor-specific initialization commands if register data matches this pattern + vendor_config.init_cmds = vendor_specific_init_new; + vendor_config.init_cmds_size = sizeof(vendor_specific_init_new) / sizeof(st77916_lcd_init_cmd_t); + printf("Vendor-specific initialization for case 2.\n"); + } + printf("------------------------------------- End of version selection------------------------------------- \r\n"); + + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = QSPI_PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, // Implemented by LCD command `36h` + .bits_per_pixel = QSPI_LCD_BIT_PER_PIXEL, // Implemented by LCD command `3Ah` (16/18) + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st77916(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_disp_on_off(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeTca9554(); + InitializeSpi(); + Initializest77916Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, I2S_STD_SLOT_LEFT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN, I2S_STD_SLOT_RIGHT); // I2S_STD_SLOT_LEFT / I2S_STD_SLOT_RIGHT / I2S_STD_SLOT_BOTH + + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/esp32-s3-touch-lcd-3.5/README.md b/main/boards/esp32-s3-touch-lcd-3.5/README.md new file mode 100644 index 0000000..78b6949 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-3.5/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-3.5 +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-3.5.htm \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-3.5/config.h b/main/boards/esp32-s3-touch-lcd-3.5/config.h new file mode 100644 index 0000000..7852904 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-3.5/config.h @@ -0,0 +1,69 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_15 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_16 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SPI_MODE 0 +#define DISPLAY_CS_PIN GPIO_NUM_NC +#define DISPLAY_MOSI_PIN GPIO_NUM_1 +#define DISPLAY_MISO_PIN GPIO_NUM_2 +#define DISPLAY_CLK_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_3 +#define DISPLAY_RST_PIN GPIO_NUM_NC + + + +#define DISPLAY_WIDTH 480 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_BGR +#define DISPLAY_INVERT_COLOR true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_6 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#define CAM_PIN_PWDN GPIO_NUM_NC +#define CAM_PIN_RESET GPIO_NUM_NC +#define CAM_PIN_VSYNC GPIO_NUM_17 +#define CAM_PIN_HREF GPIO_NUM_18 +#define CAM_PIN_PCLK GPIO_NUM_41 +#define CAM_PIN_XCLK GPIO_NUM_38 +#define CAM_PIN_SIOD GPIO_NUM_NC +#define CAM_PIN_SIOC GPIO_NUM_NC +#define CAM_PIN_D0 GPIO_NUM_45 +#define CAM_PIN_D1 GPIO_NUM_47 +#define CAM_PIN_D2 GPIO_NUM_48 +#define CAM_PIN_D3 GPIO_NUM_46 +#define CAM_PIN_D4 GPIO_NUM_42 +#define CAM_PIN_D5 GPIO_NUM_40 +#define CAM_PIN_D6 GPIO_NUM_39 +#define CAM_PIN_D7 GPIO_NUM_21 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/esp32-s3-touch-lcd-3.5/config.json b/main/boards/esp32-s3-touch-lcd-3.5/config.json new file mode 100644 index 0000000..7c6e5f1 --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-3.5/config.json @@ -0,0 +1,19 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32-s3-touch-lcd-3.5", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y", + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_640X480_6FPS=y", + "CONFIG_CAMERA_OV2640_DVP_IF_FORMAT_INDEX_DEFAULT=1", + "CONFIG_CAMERA_OV5640=y", + "CONFIG_CAMERA_OV5640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5640_DVP_YUV422_800X600_10FPS=y", + "CONFIG_CAMERA_OV5640_DVP_IF_FORMAT_INDEX_DEFAULT=0" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32-s3-touch-lcd-3.5/esp32-s3-touch-lcd-3.5.cc b/main/boards/esp32-s3-touch-lcd-3.5/esp32-s3-touch-lcd-3.5.cc new file mode 100644 index 0000000..9c2debb --- /dev/null +++ b/main/boards/esp32-s3-touch-lcd-3.5/esp32-s3-touch-lcd-3.5.cc @@ -0,0 +1,373 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "mcp_server.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include + +#include +#include "esp_io_expander_tca9554.h" + +#include "axp2101.h" +#include "power_save_timer.h" + +#include +#include + +#include "esp32_camera.h" + +#define TAG "waveshare_lcd_3_5" + +class Pmic : public Axp2101 { + public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + WriteReg(0x96, (1500 - 500) / 100); + WriteReg(0x97, (2800 - 500) / 100); + + // Enable ALDO1 BLDO1 BLDO2 + WriteReg(0x90, 0x31); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } + }; + +typedef struct { + int cmd; /*OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) + { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_OUTPUT); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_1, 1); + ESP_ERROR_CHECK(ret); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = DISPLAY_MISO_PIN; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAM_PIN_D0, + [1] = CAM_PIN_D1, + [2] = CAM_PIN_D2, + [3] = CAM_PIN_D3, + [4] = CAM_PIN_D4, + [5] = CAM_PIN_D5, + [6] = CAM_PIN_D6, + [7] = CAM_PIN_D7, + }, + .vsync_io = CAM_PIN_VSYNC, + .de_io = CAM_PIN_HREF, + .pclk_io = CAM_PIN_PCLK, + .xclk_io = CAM_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, // 不初始化新的 SCCB,使用现有的 I2C 总线 + .i2c_handle = i2c_bus_, // 使用现有的 I2C 总线句柄 + .freq = 100000, // 100kHz + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAM_PIN_RESET, + .pwdn_pin = CAM_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = 12000000, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + + } + + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 1, + .mirror_x = 1, + .mirror_y = 1, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_FT5x06_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_ft5x06(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + st7796_vendor_config_t st7796_vendor_config = { + .init_cmds = st7796_lcd_init_cmds, + .init_cmds_size = sizeof(st7796_lcd_init_cmds) / sizeof(st7796_lcd_init_cmd_t), + }; + + // 初始化液晶屏驱动芯片 + ESP_LOGI(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &st7796_vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeTca9554(); + InitializeAxp2101(); + InitializeSpi(); + InitializeLcdDisplay(); + // 解决部分开机黑屏的问题 + if (esp_reset_reason() == ESP_RST_POWERON) { + fflush(stdout); + esp_restart(); + } + InitializeTouch(); + InitializeButtons(); + InitializeCamera(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/esp32s3-korvo2-v3/config.h b/main/boards/esp32s3-korvo2-v3/config.h new file mode 100644 index 0000000..afb1dfa --- /dev/null +++ b/main/boards/esp32s3-korvo2-v3/config.h @@ -0,0 +1,81 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_48 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_17 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_18 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_5 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#ifdef CONFIG_ESP32S3_KORVO2_V3_LCD_ST7789 +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 280 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY true +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define BACKLIGHT_INVERT false + +#define DISPLAY_OFFSET_X 20 +#define DISPLAY_OFFSET_Y 0 +#endif + +#ifdef CONFIG_ESP32S3_KORVO2_V3_LCD_ILI9341 +#define LCD_TYPE_ILI9341_SERIAL +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define BACKLIGHT_INVERT false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#endif + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +/* Camera pins */ +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_XCLK GPIO_NUM_40 +#define CAMERA_PIN_SIOD GPIO_NUM_17 +#define CAMERA_PIN_SIOC GPIO_NUM_18 + +#define CAMERA_PIN_D7 GPIO_NUM_39 +#define CAMERA_PIN_D6 GPIO_NUM_41 +#define CAMERA_PIN_D5 GPIO_NUM_42 +#define CAMERA_PIN_D4 GPIO_NUM_12 +#define CAMERA_PIN_D3 GPIO_NUM_3 +#define CAMERA_PIN_D2 GPIO_NUM_14 +#define CAMERA_PIN_D1 GPIO_NUM_47 +#define CAMERA_PIN_D0 GPIO_NUM_13 +#define CAMERA_PIN_VSYNC GPIO_NUM_21 +#define CAMERA_PIN_HREF GPIO_NUM_38 +#define CAMERA_PIN_PCLK GPIO_NUM_11 + +#define XCLK_FREQ_HZ 20000000 +#endif // _BOARD_CONFIG_H_ \ No newline at end of file diff --git a/main/boards/esp32s3-korvo2-v3/config.json b/main/boards/esp32s3-korvo2-v3/config.json new file mode 100644 index 0000000..36110a1 --- /dev/null +++ b/main/boards/esp32s3-korvo2-v3/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "esp32s3-korvo2-v3", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/esp32s3-korvo2-v3/esp32s3_korvo2_v3_board.cc b/main/boards/esp32s3-korvo2-v3/esp32s3_korvo2_v3_board.cc new file mode 100644 index 0000000..920ddc5 --- /dev/null +++ b/main/boards/esp32s3-korvo2-v3/esp32s3_korvo2_v3_board.cc @@ -0,0 +1,416 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include +#include "esp32_camera.h" + +#define TAG "esp32s3_korvo2_v3" +/* ADC Buttons */ +typedef enum { + BSP_ADC_BUTTON_REC, + BSP_ADC_BUTTON_VOL_MUTE, + BSP_ADC_BUTTON_PLAY, + BSP_ADC_BUTTON_SET, + BSP_ADC_BUTTON_VOL_DOWN, + BSP_ADC_BUTTON_VOL_UP, + BSP_ADC_BUTTON_NUM +} bsp_adc_button_t; + +// Init ili9341 by custom cmd +static const ili9341_lcd_init_cmd_t vendor_specific_init[] = { + {0xC8, (uint8_t []){0xFF, 0x93, 0x42}, 3, 0}, + {0xC0, (uint8_t []){0x0E, 0x0E}, 2, 0}, + {0xC5, (uint8_t []){0xD0}, 1, 0}, + {0xC1, (uint8_t []){0x02}, 1, 0}, + {0xB4, (uint8_t []){0x02}, 1, 0}, + {0xE0, (uint8_t []){0x00, 0x03, 0x08, 0x06, 0x13, 0x09, 0x39, 0x39, 0x48, 0x02, 0x0a, 0x08, 0x17, 0x17, 0x0F}, 15, 0}, + {0xE1, (uint8_t []){0x00, 0x28, 0x29, 0x01, 0x0d, 0x03, 0x3f, 0x33, 0x52, 0x04, 0x0f, 0x0e, 0x37, 0x38, 0x0F}, 15, 0}, + + {0xB1, (uint8_t []){00, 0x1B}, 2, 0}, + {0x36, (uint8_t []){0x08}, 1, 0}, + {0x3A, (uint8_t []){0x55}, 1, 0}, + {0xB7, (uint8_t []){0x06}, 1, 0}, + + {0x11, (uint8_t []){0}, 0x80, 0}, + {0x29, (uint8_t []){0}, 0x80, 0}, + + {0, (uint8_t []){0}, 0xff, 0}, +}; + +class Esp32S3Korvo2V3Board : public WifiBoard { +private: + Button boot_button_; + Button* adc_button_[BSP_ADC_BUTTON_NUM]; +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) + adc_oneshot_unit_handle_t bsp_adc_handle = NULL; +#endif + i2c_master_bus_handle_t i2c_bus_; + LcdDisplay* display_; + esp_io_expander_handle_t io_expander_ = NULL; + Esp32Camera* camera_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + void InitializeTca9554() { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000, &io_expander_); + if(ret != ESP_OK) { + ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9554A_ADDRESS_000, &io_expander_); + if(ret != ESP_OK) { + ESP_LOGE(TAG, "TCA9554 create returned error"); + return; + } + } + // 配置IO0-IO3为输出模式 + ESP_ERROR_CHECK(esp_io_expander_set_dir(io_expander_, + IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 | + IO_EXPANDER_PIN_NUM_2 | IO_EXPANDER_PIN_NUM_3, + IO_EXPANDER_OUTPUT)); + + // 复位LCD和TouchPad + ESP_ERROR_CHECK(esp_io_expander_set_level(io_expander_, + IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 | IO_EXPANDER_PIN_NUM_2, 1)); + vTaskDelay(pdMS_TO_TICKS(300)); + ESP_ERROR_CHECK(esp_io_expander_set_level(io_expander_, + IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 | IO_EXPANDER_PIN_NUM_2, 0)); + vTaskDelay(pdMS_TO_TICKS(300)); + ESP_ERROR_CHECK(esp_io_expander_set_level(io_expander_, + IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 | IO_EXPANDER_PIN_NUM_2, 1)); + } + + void EnableLcdCs() { + if(io_expander_ != NULL) { + esp_io_expander_set_level(io_expander_, IO_EXPANDER_PIN_NUM_3, 0);// 置低 LCD CS + } + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_0; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_1; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void ChangeVol(int val) { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + val; + if (volume > 100) { + volume = 100; + } + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + } + + void MuteVol() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume(); + if (volume > 1) { + volume = 0; + } else { + volume = 50; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + } + + void InitializeButtons() { + button_adc_config_t adc_cfg = {}; + adc_cfg.adc_channel = ADC_CHANNEL_4; // ADC1 channel 0 is GPIO5 +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) + const adc_oneshot_unit_init_cfg_t init_config1 = { + .unit_id = ADC_UNIT_1, + }; + adc_oneshot_new_unit(&init_config1, &bsp_adc_handle); + adc_cfg.adc_handle = &bsp_adc_handle; +#endif + adc_cfg.button_index = BSP_ADC_BUTTON_REC; + adc_cfg.min = 2310; // middle is 2410mV + adc_cfg.max = 2510; + adc_button_[0] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_VOL_MUTE; + adc_cfg.min = 1880; // middle is 1980mV + adc_cfg.max = 2080; + adc_button_[1] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_PLAY; + adc_cfg.min = 1550; // middle is 1650mV + adc_cfg.max = 1750; + adc_button_[2] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_SET; + adc_cfg.min = 1015; // middle is 1115mV + adc_cfg.max = 1215; + adc_button_[3] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_VOL_DOWN; + adc_cfg.min = 720; // middle is 820mV + adc_cfg.max = 920; + adc_button_[4] = new AdcButton(adc_cfg); + + adc_cfg.button_index = BSP_ADC_BUTTON_VOL_UP; + adc_cfg.min = 280; // middle is 380mV + adc_cfg.max = 480; + adc_button_[5] = new AdcButton(adc_cfg); + + auto volume_up_button = adc_button_[BSP_ADC_BUTTON_VOL_UP]; + volume_up_button->OnClick([this]() {ChangeVol(10);}); + volume_up_button->OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + auto volume_down_button = adc_button_[BSP_ADC_BUTTON_VOL_DOWN]; + volume_down_button->OnClick([this]() {ChangeVol(-10);}); + volume_down_button->OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + auto volume_mute_button = adc_button_[BSP_ADC_BUTTON_VOL_MUTE]; + volume_mute_button->OnClick([this]() {MuteVol();}); + + auto play_button = adc_button_[BSP_ADC_BUTTON_PLAY]; + play_button->OnClick([this]() { + ESP_LOGI(TAG, " TODO %s:%d\n", __func__, __LINE__); + }); + + auto set_button = adc_button_[BSP_ADC_BUTTON_SET]; + set_button->OnClick([this]() { + ESP_LOGI(TAG, "TODO %s:%d\n", __func__, __LINE__); + }); + + auto rec_button = adc_button_[BSP_ADC_BUTTON_REC]; + rec_button->OnClick([this]() { + ESP_LOGI(TAG, "TODO %s:%d\n", __func__, __LINE__); + }); + boot_button_.OnClick([this]() {}); + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeIli9341Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_NC; + io_config.dc_gpio_num = GPIO_NUM_2; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const ili9341_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(ili9341_lcd_init_cmd_t), + }; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + // panel_config.flags.reset_active_high = 0, + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void *)&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + EnableLcdCs(); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_46; + io_config.dc_gpio_num = GPIO_NUM_2; + io_config.spi_mode = 0; + io_config.pclk_hz = 60 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + EnableLcdCs(); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + Esp32S3Korvo2V3Board() : boot_button_(BOOT_BUTTON_GPIO) { + ESP_LOGI(TAG, "Initializing esp32s3_korvo2_v3 Board"); + InitializeI2c(); + I2cDetect(); + InitializeTca9554(); + InitializeCamera(); + InitializeSpi(); + InitializeButtons(); + #ifdef LCD_TYPE_ILI9341_SERIAL + InitializeIli9341Display(); + #else + InitializeSt7789Display(); + #endif + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(Esp32S3Korvo2V3Board); diff --git a/main/boards/genjutech-s3-1.54tft/config.h b/main/boards/genjutech-s3-1.54tft/config.h new file mode 100644 index 0000000..4f3aad8 --- /dev/null +++ b/main/boards/genjutech-s3-1.54tft/config.h @@ -0,0 +1,43 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_11 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_10 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_21 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_9 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_1 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_42 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_41 + +#define DISPLAY_SDA GPIO_NUM_3 +#define DISPLAY_SCL GPIO_NUM_4 +#define DISPLAY_DC GPIO_NUM_5 +#define DISPLAY_CS GPIO_NUM_6 +#define DISPLAY_RES GPIO_NUM_7 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_2 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ \ No newline at end of file diff --git a/main/boards/genjutech-s3-1.54tft/config.json b/main/boards/genjutech-s3-1.54tft/config.json new file mode 100644 index 0000000..a8c65f8 --- /dev/null +++ b/main/boards/genjutech-s3-1.54tft/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "genjutech-s3-1.54tft", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/genjutech-s3-1.54tft/genjutech-s3-1.54tft.cc b/main/boards/genjutech-s3-1.54tft/genjutech-s3-1.54tft.cc new file mode 100644 index 0000000..99794fb --- /dev/null +++ b/main/boards/genjutech-s3-1.54tft/genjutech-s3-1.54tft.cc @@ -0,0 +1,259 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include +#include +#include +#include "power_save_timer.h" + +#include "assets/lang_config.h" +#include "power_manager.h" + +#define TAG "GenJuTech_s3_1_54TFT" + +class SparkBotEs8311AudioCodec : public Es8311AudioCodec { + private: + + public: + SparkBotEs8311AudioCodec(void* i2c_master_handle, i2c_port_t i2c_port, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, bool use_mclk = true) + : Es8311AudioCodec(i2c_master_handle, i2c_port, input_sample_rate, output_sample_rate, + mclk, bclk, ws, dout, din,pa_pin, es8311_addr, use_mclk = true) {} + + void EnableOutput(bool enable) override { + if (enable == output_enabled_) { + return; + } + if (enable) { + Es8311AudioCodec::EnableOutput(enable); + } else { + // Nothing todo because the display io and PA io conflict + } + } + }; + +class GenJuTech_s3_1_54TFT : public WifiBoard { +private: + // i2c_master_bus_handle_t display_i2c_bus_; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + LcdDisplay* display_; + i2c_master_bus_handle_t codec_i2c_bus_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_16); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + // 第一个参数不为 -1 时,进入睡眠会关闭音频输入 + power_save_timer_ = new PowerSaveTimer(240, 60); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + // boot_button_.OnPressDown([this]() { + // Application::GetInstance().StartListening(); + // }); + // boot_button_.OnPressUp([this]() { + // Application::GetInstance().StopListening(); + // }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + gpio_config_t config = { + .pin_bit_mask = (1ULL << DISPLAY_RES), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + ESP_ERROR_CHECK(gpio_config(&config)); + gpio_set_level(DISPLAY_RES, 0); + vTaskDelay(20); + gpio_set_level(DISPLAY_RES, 1); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + GenJuTech_s3_1_54TFT() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + ESP_LOGI(TAG, "Initializing GenJuTech S3 1.54 Board"); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static SparkBotEs8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(GenJuTech_s3_1_54TFT); diff --git a/main/boards/genjutech-s3-1.54tft/power_manager.h b/main/boards/genjutech-s3-1.54tft/power_manager.h new file mode 100644 index 0000000..f2e385d --- /dev/null +++ b/main/boards/genjutech-s3-1.54tft/power_manager.h @@ -0,0 +1,186 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_4, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1280, 0}, + {1334, 20}, + {1388, 40}, + {1442, 60}, + {1496, 80}, + {1550, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_2, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_4, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/hu-087/README.md b/main/boards/hu-087/README.md new file mode 100644 index 0000000..8dfe066 --- /dev/null +++ b/main/boards/hu-087/README.md @@ -0,0 +1,7 @@ + +[product](https://fr.aliexpress.com/item/1005010207331462.html) + +One of the cheapest kit in a watch form factor. + +## Programming ## +Before assembling the product, unglue the battery from the board to access the programming header. You'll need a ESP32 programming dongle with control of the EN and IO0 pins. The USB connector is not wired to the USB pins of the ESP32-S3 USB interface and can only be used for charging. diff --git a/main/boards/hu-087/config.h b/main/boards/hu-087/config.h new file mode 100644 index 0000000..dff8b3f --- /dev/null +++ b/main/boards/hu-087/config.h @@ -0,0 +1,28 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 +#define AUDIO_I2S_SPK_GPIO_CTLR GPIO_NUM_17 + + +#define TOUCH_BUTTON_GPIO GPIO_NUM_18 + +#define DISPLAY_SDA_PIN GPIO_NUM_41 +#define DISPLAY_SCL_PIN GPIO_NUM_42 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 + +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/hu-087/config.json b/main/boards/hu-087/config.json new file mode 100644 index 0000000..7616766 --- /dev/null +++ b/main/boards/hu-087/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "hu-087", + "sdkconfig_append": [] + } + ] +} diff --git a/main/boards/hu-087/hu_087_board.cc b/main/boards/hu-087/hu_087_board.cc new file mode 100644 index 0000000..e6d55ba --- /dev/null +++ b/main/boards/hu-087/hu_087_board.cc @@ -0,0 +1,152 @@ +#include +#include +#include +#include +#include + +#include "application.h" +#include "assets/lang_config.h" +#include "boards/common/wifi_board.h" +#include "button.h" +#include "codecs/no_audio_codec.h" +#include "config.h" +#include "display/oled_display.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "system_reset.h" + +#define TAG "Hu087Board" + +class Hu087Board : public WifiBoard { + private: + i2c_master_bus_handle_t display_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button touch_button_; + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = + { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = + { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK( + esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK( + esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void initializeAmpCtrl() { + gpio_config_t io_conf = { + .pin_bit_mask = (1ULL << AUDIO_I2S_SPK_GPIO_CTLR), // Select GPIO 2 + .mode = GPIO_MODE_OUTPUT, // Set as output + .pull_up_en = GPIO_PULLUP_ENABLE, // Disable pull-up + .pull_down_en = GPIO_PULLDOWN_DISABLE, // Disable pull-down + .intr_type = GPIO_INTR_DISABLE // Disable interrupts + }; + gpio_config(&io_conf); + gpio_set_level(AUDIO_I2S_SPK_GPIO_CTLR, 1); + }; + + void InitializeButtons() { + touch_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + touch_button_.OnLongPress([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } // Need to implement logic to lower volume + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + + std::to_string(volume)); + }); + } + + public: + Hu087Board() : touch_button_(TOUCH_BUTTON_GPIO) { + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + initializeAmpCtrl(); // Could control the amp ctrl pin throught voice + // detection i guess + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec( + AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, + AUDIO_I2S_SPK_GPIO_DOUT, I2S_STD_SLOT_RIGHT, AUDIO_I2S_MIC_GPIO_SCK, + AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN, I2S_STD_SLOT_RIGHT); + return &audio_codec; + } + + virtual Display* GetDisplay() override { return display_; } +}; + +DECLARE_BOARD(Hu087Board); diff --git a/main/boards/jiuchuan-s3/README.md b/main/boards/jiuchuan-s3/README.md new file mode 100644 index 0000000..1675ebf --- /dev/null +++ b/main/boards/jiuchuan-s3/README.md @@ -0,0 +1,24 @@ +# jiuchuan-xiaozhi-sound +九川科技小智AI音箱 + +## 🛠️ 编译指南 +**开发环境**:ESP-IDF v5.4.1 + +### 编译步骤: +> ⚠️ **提示**:若在编译过程中访问在线库失败,可以尝试切换加速器状态,或修改 [idf_component.yml] 文件,替换为国内镜像源。 + +1. 使用 VSCode 打开项目文件夹; +2. 清除工程(Clean Project); +3. 设置 ESP-IDF 版本为 `v5.4.1`; +4. 点击 VSCode 右下角提示,生成 [compile_commands.json] 文件; +5. 设置目标设备为 `[esp32s3] -> [JTAG]`; +6. 打开 **SDK Configuration Editor**; +7. 设置 **Board Type** 为 **九川科技**; +8. 保存配置并开始编译。 + +## 🔌 烧录步骤 +1. 使用数据线连接电脑与音箱; +2. 关闭设备电源后,长按电源键不松手; +3. 在烧录工具中选择对应的串口(COM Port); +4. 点击烧录按钮,选择 UART 模式; +5. 烧录完成前请勿松开电源键。 \ No newline at end of file diff --git a/main/boards/jiuchuan-s3/config.h b/main/boards/jiuchuan-s3/config.h new file mode 100644 index 0000000..d689527 --- /dev/null +++ b/main/boards/jiuchuan-s3/config.h @@ -0,0 +1,52 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_13 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_12 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_42 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_1 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_2 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + + +#define BUILTIN_LED_GPIO GPIO_NUM_10 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_3 +#define PWR_EN_GPIO GPIO_NUM_5 +#define PWR_ADC_GPIO GPIO_NUM_4 +#define PWR_BUTTON_TIME 3000000U + +#define WIFI_BUTTON_GPIO GPIO_NUM_6 +#define CMD_BUTTON_GPIO GPIO_NUM_7 + + +#define DISPLAY_SPI_SCK_PIN GPIO_NUM_41 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_40 +#define DISPLAY_DC_PIN GPIO_NUM_39 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_9 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_46 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/jiuchuan-s3/config.json b/main/boards/jiuchuan-s3/config.json new file mode 100644 index 0000000..d1f610f --- /dev/null +++ b/main/boards/jiuchuan-s3/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "jiuchuan-s3", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.c b/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.c new file mode 100644 index 0000000..b8d0e9a --- /dev/null +++ b/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.c @@ -0,0 +1,384 @@ +/* + * SPDX-FileCopyrightText: 2021-2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + + #include + #include + #include "sdkconfig.h" + #include + #if CONFIG_LCD_ENABLE_DEBUG_LOG + // The local log level must be defined before including esp_log.h + // Set the maximum log level for this source file + #define LOG_LOCAL_LEVEL ESP_LOG_DEBUG + #endif + + #include "freertos/FreeRTOS.h" + #include "freertos/task.h" + #include "esp_lcd_panel_interface.h" + #include "esp_lcd_panel_io.h" + #include "esp_lcd_panel_vendor.h" + #include "esp_lcd_panel_ops.h" + #include "esp_lcd_panel_commands.h" + #include "driver/gpio.h" + #include "esp_log.h" + #include "esp_check.h" + #include "esp_compiler.h" + /* GC9309NA LCD controller driver for ESP-IDF + * SPDX-FileCopyrightText: 2024 Your Name + * SPDX-License-Identifier: Apache-2.0 + */ + + #include "freertos/FreeRTOS.h" + #include "freertos/task.h" + #include "esp_lcd_panel_interface.h" + #include "esp_lcd_panel_io.h" + #include "esp_check.h" + #include "driver/gpio.h" + + + // GC9309NA Command Set + #define GC9309NA_CMD_SLPIN 0x10 + #define GC9309NA_CMD_SLPOUT 0x11 + #define GC9309NA_CMD_INVOFF 0x20 + #define GC9309NA_CMD_INVON 0x21 + #define GC9309NA_CMD_DISPOFF 0x28 + #define GC9309NA_CMD_DISPON 0x29 + #define GC9309NA_CMD_CASET 0x2A + #define GC9309NA_CMD_RASET 0x2B + #define GC9309NA_CMD_RAMWR 0x2C + #define GC9309NA_CMD_MADCTL 0x36 + #define GC9309NA_CMD_COLMOD 0x3A + #define GC9309NA_CMD_TEOFF 0x34 + #define GC9309NA_CMD_TEON 0x35 + #define GC9309NA_CMD_WRDISBV 0x51 + #define GC9309NA_CMD_WRCTRLD 0x53 + + // Manufacturer Commands + #define GC9309NA_CMD_SETGAMMA1 0xF0 + #define GC9309NA_CMD_SETGAMMA2 0xF1 + #define GC9309NA_CMD_PWRCTRL1 0x67 + #define GC9309NA_CMD_PWRCTRL2 0x68 + #define GC9309NA_CMD_PWRCTRL3 0x66 + #define GC9309NA_CMD_PWRCTRL4 0xCA + #define GC9309NA_CMD_PWRCTRL5 0xCB + #define GC9309NA_CMD_DINVCTRL 0xB5 + #define GC9309NA_CMD_REG_ENABLE1 0xFE + #define GC9309NA_CMD_REG_ENABLE2 0xEF + + // 自检模式颜色定义 + + + static const char *TAG = "lcd_panel.gc9309na"; + + typedef struct { + esp_lcd_panel_t base; + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + bool reset_level; + int x_gap; + int y_gap; + uint8_t madctl_val; + uint8_t colmod_val; + uint16_t te_scanline; + uint8_t fb_bits_per_pixel; + } gc9309na_panel_t; + + static esp_err_t panel_gc9309na_del(esp_lcd_panel_t *panel); + static esp_err_t panel_gc9309na_reset(esp_lcd_panel_t *panel); + static esp_err_t panel_gc9309na_init(esp_lcd_panel_t *panel); + static esp_err_t panel_gc9309na_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data); + static esp_err_t panel_gc9309na_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); + static esp_err_t panel_gc9309na_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); + static esp_err_t panel_gc9309na_swap_xy(esp_lcd_panel_t *panel, bool swap_axes); + static esp_err_t panel_gc9309na_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap); + static esp_err_t panel_gc9309na_disp_on_off(esp_lcd_panel_t *panel, bool off); + static esp_err_t panel_gc9309na_sleep(esp_lcd_panel_t *panel, bool sleep); + + + esp_err_t esp_lcd_new_panel_gc9309na(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, esp_lcd_panel_handle_t *ret_panel) + { + esp_err_t ret = ESP_OK; + gc9309na_panel_t *gc9309 = NULL; + + ESP_GOTO_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, err, TAG, "invalid arg"); + + gc9309 = calloc(1, sizeof(gc9309na_panel_t)); + ESP_GOTO_ON_FALSE(gc9309, ESP_ERR_NO_MEM, err, TAG, "no mem"); + + + // Hardware reset GPIO config + if (panel_dev_config->reset_gpio_num >= 0) { + gpio_config_t io_conf = { + .mode = GPIO_MODE_OUTPUT, + .pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num, + }; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "GPIO config failed"); + } + + gc9309->colmod_val = 0x55; // RGB565 + // Initial register values + + gc9309->fb_bits_per_pixel = 16; + gc9309->io = io; + gc9309->reset_gpio_num = panel_dev_config->reset_gpio_num; + gc9309->reset_level = panel_dev_config->flags.reset_active_high; + gc9309->x_gap = 0; + gc9309->y_gap = 0; + + // Function pointers + gc9309->base.del = panel_gc9309na_del; + gc9309->base.reset = panel_gc9309na_reset; + gc9309->base.init = panel_gc9309na_init; + gc9309->base.draw_bitmap = panel_gc9309na_draw_bitmap; + gc9309->base.invert_color = panel_gc9309na_invert_color; + gc9309->base.set_gap = panel_gc9309na_set_gap; + gc9309->base.mirror = panel_gc9309na_mirror; + gc9309->base.swap_xy = panel_gc9309na_swap_xy; + gc9309->base.disp_on_off = panel_gc9309na_disp_on_off; + gc9309->base.disp_sleep = panel_gc9309na_sleep; + + *ret_panel = &(gc9309->base); + ESP_LOGI(TAG, "New GC9309NA panel @%p", gc9309); + return ESP_OK; + + err: + if (gc9309) { + if (panel_dev_config->reset_gpio_num >= 0) { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(gc9309); + } + return ret; + } + + static esp_err_t panel_gc9309na_del(esp_lcd_panel_t *panel) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + + if (gc9309->reset_gpio_num >= 0) { + gpio_reset_pin(gc9309->reset_gpio_num); + } + free(gc9309); + ESP_LOGI(TAG, "Del GC9309NA panel"); + return ESP_OK; + } + + static esp_err_t panel_gc9309na_reset(esp_lcd_panel_t *panel) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + + if (gc9309->reset_gpio_num >= 0) { + // Hardware reset + gpio_set_level(gc9309->reset_gpio_num, gc9309->reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9309->reset_gpio_num, !gc9309->reset_level); + vTaskDelay(pdMS_TO_TICKS(120)); + } else { + // Software reset + // uint8_t unlock_cmd[] = {GC9309NA_CMD_REG_ENABLE1, GC9309NA_CMD_REG_ENABLE2}; + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(gc9309->io, 0xFE, unlock_cmd, 2), + // TAG, "Unlock failed"); + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(gc9309->io, LCD_CMD_SWRESET, NULL, 0), + // TAG, "SW Reset failed"); + vTaskDelay(pdMS_TO_TICKS(120)); + } + return ESP_OK; + } + static esp_err_t panel_gc9309na_init(esp_lcd_panel_t *panel) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9309->io; + + // Unlock commands + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xFE, NULL, 0), TAG, "Unlock cmd1 failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xEF, NULL, 0), TAG, "Unlock cmd2 failed"); + + // Sleep out command + //ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x11, NULL, 0), TAG, "Sleep out failed"); + //vTaskDelay(pdMS_TO_TICKS(80)); + + // Timing control commands + //ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xE8, (uint8_t[]){0xA0}, 1), TAG, "Timing control failed"); + //ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xE8, (uint8_t[]){0xF0}, 1), TAG, "Timing control failed"); + + // Display on command + //ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x29, NULL, 0), TAG, "Display on failed"); + // vTaskDelay(pdMS_TO_TICKS(10)); + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x80, (uint8_t[]){0xC0}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x81, (uint8_t[]){0x01}, 1), TAG, "DINV failed"); + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x82, (uint8_t[]){0x07}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x83, (uint8_t[]){0x38}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x88, (uint8_t[]){0x64}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x89, (uint8_t[]){0x86}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x8B, (uint8_t[]){0x3C}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x8D, (uint8_t[]){0x51}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x8E, (uint8_t[]){0x70}, 1), TAG, "DINV failed"); + + //高低位交换 + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xB4, (uint8_t[]){0x80}, 1), TAG, "DINV failed"); + + gc9309->colmod_val = 0x05; // RGB565 + gc9309->madctl_val = 0x48; // BGR顺序,设置bit3=1(即0x08) + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9309NA_CMD_COLMOD, &gc9309->colmod_val, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9309NA_CMD_MADCTL, &gc9309->madctl_val, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0XBF, (uint8_t[]){0X1F}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x7d, (uint8_t[]){0x45,0x06}, 2), TAG, "DINV failed"); + // Continue from where you left off + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xEE, (uint8_t[]){0x00,0x06}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0XF4, (uint8_t[]){0x53}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xF6, (uint8_t[]){0x17,0x08}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x70, (uint8_t[]){0x4F,0x4F}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x71, (uint8_t[]){0x12,0x20}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x72, (uint8_t[]){0x12,0x20}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xB5, (uint8_t[]){0x50}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xBA, (uint8_t[]){0x00}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xEC, (uint8_t[]){0x71}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x7b, (uint8_t[]){0x00,0x0d}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x7c, (uint8_t[]){0x0d,0x03}, 2), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0XF5, (uint8_t[]){0x02,0x10,0x12}, 3), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xF0, (uint8_t[]){0x0C,0x11,0x0b,0x0a,0x05,0x32,0x44,0x8e,0x9a,0x29,0x2E,0x5f}, 12), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xF1, (uint8_t[]){0x0B,0x11,0x0b,0x07,0x07,0x32,0x45,0xBd,0x8D,0x21,0x28,0xAf}, 12), TAG, "DINV failed"); + + // 240x296 resolution settings + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x2a, (uint8_t[]){0x00,0x00,0x00,0xef}, 4), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x2b, (uint8_t[]){0x00,0x00,0x01,0x27}, 4), TAG, "DINV failed"); + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x66, (uint8_t[]){0x2C}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x67, (uint8_t[]){0x18}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x68, (uint8_t[]){0x3E}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xCA, (uint8_t[]){0x0E}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xe8, (uint8_t[]){0xf0}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xCB, (uint8_t[]){0x06}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xB6, (uint8_t[]){0x5C,0x40,0x40}, 3), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xCC, (uint8_t[]){0x33}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xCD, (uint8_t[]){0x33}, 1), TAG, "DINV failed"); + + // Sleep out command + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x11, NULL, 0), TAG, "Sleep out failed"); + vTaskDelay(pdMS_TO_TICKS(80)); + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xe8, (uint8_t[]){0xA0}, 1), TAG, "DINV failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xe8, (uint8_t[]){0xf0}, 1), TAG, "DINV failed"); + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xfe, NULL, 0), TAG, "unlock cmd1 failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0xee, NULL, 0), TAG, "unlock cmd2 failed"); + + // Display on command + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x29, NULL, 0), TAG, "Display on failed"); + + // Memory write command + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x2c, NULL, 0), TAG, "Memory write failed"); + vTaskDelay(pdMS_TO_TICKS(10)); + return ESP_OK; + } + + + static esp_err_t panel_gc9309na_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + + + esp_lcd_panel_io_handle_t io = gc9309->io; + + x_start += gc9309->x_gap; + x_end += gc9309->x_gap; + y_start += gc9309->y_gap; + y_end += gc9309->y_gap; + + // define an area of frame memory where MCU can access + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_CASET, (uint8_t[]) { + (x_start >> 8) & 0xFF, + x_start & 0xFF, + ((x_end - 1) >> 8) & 0xFF, + (x_end - 1) & 0xFF, + }, 4), TAG, "io tx param failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_RASET, (uint8_t[]) { + (y_start >> 8) & 0xFF, + y_start & 0xFF, + ((y_end - 1) >> 8) & 0xFF, + (y_end - 1) & 0xFF, + }, 4), TAG, "io tx param failed"); + // transfer frame buffer + size_t len = (x_end - x_start) * (y_end - y_start) * gc9309->fb_bits_per_pixel / 8; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_color(io, LCD_CMD_RAMWR, color_data, len), TAG, "io tx color failed"); + + return ESP_OK; + } + + static esp_err_t panel_gc9309na_invert_color(esp_lcd_panel_t *panel, bool invert_color_data) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9309->io; + int command = 0; + if (invert_color_data) { + command = LCD_CMD_INVON; + } else { + command = LCD_CMD_INVOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, + "io tx param failed"); + return ESP_OK; + } + + static esp_err_t panel_gc9309na_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) + { + // gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + // esp_lcd_panel_io_handle_t io = gc9309->io; + // if (mirror_x) { + // gc9309->madctl_val |= LCD_CMD_MX_BIT; + // } else { + // gc9309->madctl_val &= ~LCD_CMD_MX_BIT; + // } + // if (mirror_y) { + // gc9309->madctl_val |= LCD_CMD_MY_BIT; + // } else { + // gc9309->madctl_val &= ~LCD_CMD_MY_BIT; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]) { + // gc9309->madctl_val + // }, 1), TAG, "io tx param failed"); + return ESP_OK; + } + + static esp_err_t panel_gc9309na_swap_xy(esp_lcd_panel_t *panel, bool swap_axes) + { + // gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + // esp_lcd_panel_io_handle_t io = gc9309->io; + // if (swap_axes) { + // gc9309->madctl_val |= LCD_CMD_MV_BIT; + // } else { + // gc9309->madctl_val &= ~LCD_CMD_MV_BIT; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]) { + // gc9309->madctl_val + // }, 1), TAG, "io tx param failed"); + return ESP_OK; + } + + static esp_err_t panel_gc9309na_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + gc9309->x_gap = x_gap; + gc9309->y_gap = y_gap; + return ESP_OK; + } + + static esp_err_t panel_gc9309na_disp_on_off(esp_lcd_panel_t *panel, bool on_off) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + uint8_t cmd = on_off ? GC9309NA_CMD_DISPON : GC9309NA_CMD_DISPOFF; + return esp_lcd_panel_io_tx_param(gc9309->io, cmd, NULL, 0); + } + + static esp_err_t panel_gc9309na_sleep(esp_lcd_panel_t *panel, bool sleep) + { + gc9309na_panel_t *gc9309 = __containerof(panel, gc9309na_panel_t, base); + uint8_t cmd = sleep ? GC9309NA_CMD_SLPIN : GC9309NA_CMD_SLPOUT; + esp_err_t ret = esp_lcd_panel_io_tx_param(gc9309->io, cmd, NULL, 0); + vTaskDelay(pdMS_TO_TICKS(120)); + return ret; + } \ No newline at end of file diff --git a/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.h b/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.h new file mode 100644 index 0000000..0a7065b --- /dev/null +++ b/main/boards/jiuchuan-s3/esp_lcd_panel_gc9301.h @@ -0,0 +1,31 @@ +/* + * SPDX-FileCopyrightText: 2021-2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +#pragma once + +#include +#include "esp_err.h" +#include "esp_lcd_panel_dev.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Create LCD panel for model ST7789 + * + * @param[in] io LCD panel IO handle + * @param[in] panel_dev_config general panel device configuration + * @param[out] ret_panel Returned LCD panel handle + * @return + * - ESP_ERR_INVALID_ARG if parameter is invalid + * - ESP_ERR_NO_MEM if out of memory + * - ESP_OK on success + */ +esp_err_t esp_lcd_new_panel_gc9309na(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, esp_lcd_panel_handle_t *ret_panel); + +#ifdef __cplusplus +} +#endif diff --git a/main/boards/jiuchuan-s3/gpio_manager.h b/main/boards/jiuchuan-s3/gpio_manager.h new file mode 100644 index 0000000..f8e83ff --- /dev/null +++ b/main/boards/jiuchuan-s3/gpio_manager.h @@ -0,0 +1,62 @@ +#pragma once +#include +#include +#include +#include + +class GpioManager { +public: + enum class GpioMode { + INPUT, + OUTPUT, + INPUT_PULLUP, + INPUT_PULLDOWN + }; + + static void SetLevel(gpio_num_t gpio, uint32_t level) { + std::lock_guard lock(mutex_); + ESP_ERROR_CHECK(gpio_set_level(gpio, level)); + ESP_LOGD("GpioManager", "Set GPIO %d level: %d", static_cast(gpio), static_cast(level)); + } + + static int GetLevel(gpio_num_t gpio) { + std::lock_guard lock(mutex_); + int level = gpio_get_level(gpio); + ESP_LOGD("GpioManager", "Get GPIO %d level: %d", static_cast(gpio), level); + return level; + } + + static void Config(gpio_num_t gpio, GpioMode mode) { + std::lock_guard lock(mutex_); + + gpio_config_t config = {}; + config.pin_bit_mask = (1ULL << gpio); + + switch(mode) { + case GpioMode::INPUT: + config.mode = GPIO_MODE_INPUT; + config.pull_up_en = GPIO_PULLUP_DISABLE; + config.pull_down_en = GPIO_PULLDOWN_DISABLE; + break; + case GpioMode::OUTPUT: + config.mode = GPIO_MODE_OUTPUT; + break; + case GpioMode::INPUT_PULLUP: + config.mode = GPIO_MODE_INPUT; + config.pull_up_en = GPIO_PULLUP_ENABLE; + break; + case GpioMode::INPUT_PULLDOWN: + config.mode = GPIO_MODE_INPUT; + config.pull_down_en = GPIO_PULLDOWN_ENABLE; + break; + } + + ESP_ERROR_CHECK(gpio_config(&config)); + ESP_LOGI("GpioManager", "Configured GPIO %d mode: %d", gpio, static_cast(mode)); + } + +private: + static std::mutex mutex_; +}; + +std::mutex GpioManager::mutex_; \ No newline at end of file diff --git a/main/boards/jiuchuan-s3/jiuchuan_dev_board.cc b/main/boards/jiuchuan-s3/jiuchuan_dev_board.cc new file mode 100644 index 0000000..f60700f --- /dev/null +++ b/main/boards/jiuchuan-s3/jiuchuan_dev_board.cc @@ -0,0 +1,383 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" + +#include +#include +#include +#include +#include +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "esp_lcd_panel_gc9301.h" + +#include "power_save_timer.h" +#include "power_manager.h" +#include "power_controller.h" +#include "gpio_manager.h" +#include +#include + +#define BOARD_TAG "JiuchuanDevBoard" +#define __USER_GPIO_PWRDOWN__ + +// 自定义LCD显示器类,用于圆形屏幕适配 +class CustomLcdDisplay : public SpiLcdDisplay +{ +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) + { + + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES * 0.167, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES * 0.167, 0); + } +}; + +class JiuchuanDevBoard : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + Button pwr_button_; + Button wifi_button; + Button cmd_button; + LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io = NULL; + esp_lcd_panel_handle_t panel = NULL; + + // 音量映射函数:将内部音量(0-80)映射为显示音量(0-100%) + int MapVolumeForDisplay(int internal_volume) { + // 确保输入在有效范围内 + if (internal_volume < 0) internal_volume = 0; + if (internal_volume > 80) internal_volume = 80; + + // 将0-80映射到0-100 + // 公式: 显示音量 = (内部音量 / 80) * 100 + return (internal_volume * 100) / 80; + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(PWR_ADC_GPIO); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + #ifndef __USER_GPIO_PWRDOWN__ + RTC_DATA_ATTR static bool long_press_occurred = false; + esp_sleep_wakeup_cause_t cause = esp_sleep_get_wakeup_cause(); + if (cause == ESP_SLEEP_WAKEUP_EXT0) { + ESP_LOGI(TAG, "Wake up by EXT0"); + const int64_t start = esp_timer_get_time(); + ESP_LOGI(TAG, "esp_sleep_get_wakeup_cause"); + while (gpio_get_level(PWR_BUTTON_GPIO) == 0) { + if (esp_timer_get_time() - start > 3000000) { + long_press_occurred = true; + break; + } + vTaskDelay(100 / portTICK_PERIOD_MS); + } + + if (long_press_occurred) { + ESP_LOGI(TAG, "Long press wakeup"); + long_press_occurred = false; + } else { + ESP_LOGI(TAG, "Short press, return to sleep"); + ESP_ERROR_CHECK(esp_sleep_enable_ext0_wakeup(PWR_BUTTON_GPIO, 0)); + ESP_ERROR_CHECK(rtc_gpio_pullup_en(PWR_BUTTON_GPIO)); // 内部上拉 + ESP_ERROR_CHECK(rtc_gpio_pulldown_dis(PWR_BUTTON_GPIO)); + esp_deep_sleep_start(); + } + } + #endif + //一分钟进入浅睡眠,5分钟进入深睡眠关机 + power_save_timer_ = new PowerSaveTimer(-1, (60*5), -1); + // power_save_timer_ = new PowerSaveTimer(-1, 6, 10);//test + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + #ifndef __USER_GPIO_PWRDOWN__ + ESP_ERROR_CHECK(esp_sleep_enable_ext0_wakeup(PWR_BUTTON_GPIO, 0)); + ESP_ERROR_CHECK(rtc_gpio_pullup_en(PWR_BUTTON_GPIO)); // 内部上拉 + ESP_ERROR_CHECK(rtc_gpio_pulldown_dis(PWR_BUTTON_GPIO)); + + esp_lcd_panel_disp_on_off(panel, false); //关闭显示 + esp_deep_sleep_start(); + #else + rtc_gpio_set_level(PWR_EN_GPIO, 0); + rtc_gpio_hold_dis(PWR_EN_GPIO); + #endif + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + } + + void InitializeButtons() { + static bool pwrbutton_unreleased = false; + + if (gpio_get_level(GPIO_NUM_3) == 1) { + pwrbutton_unreleased = true; + } + // 配置GPIO + ESP_LOGI(TAG, "Configuring power button GPIO"); + GpioManager::Config(GPIO_NUM_3, GpioManager::GpioMode::INPUT_PULLDOWN); + + boot_button_.OnClick([this]() { + ESP_LOGI(TAG, "Boot button clicked"); + power_save_timer_->WakeUp(); + }); + + // 检查电源按钮初始状态 + ESP_LOGI(TAG, "Power button initial state: %d", GpioManager::GetLevel(PWR_BUTTON_GPIO)); + + // 高电平有效长按关机逻辑 + pwr_button_.OnPressDown([this]() { + pwrbutton_unreleased = false; + }); + pwr_button_.OnLongPress([this]() + { + ESP_LOGI(TAG, "Power button long press detected (high-active)"); + + if (pwrbutton_unreleased){ + ESP_LOGI(TAG, "开机后电源键未松开,取消关机"); + return; + } + + // 高电平有效防抖确认 + for (int i = 0; i < 5; i++) { + int level = GpioManager::GetLevel(PWR_BUTTON_GPIO); + ESP_LOGD(TAG, "Debounce check %d: GPIO%d level=%d", i+1, PWR_BUTTON_GPIO, level); + + if (level == 0) { + ESP_LOGW(TAG, "Power button inactive during confirmation - abort shutdown"); + return; + } + vTaskDelay(100 / portTICK_PERIOD_MS); + } + + ESP_LOGI(TAG, "Confirmed power button pressed - initiating shutdown"); + power_manager_->SetPowerState(PowerState::SHUTDOWN); }); + + //单击切换状态 + pwr_button_.OnClick([this]() + { + // 获取当前应用实例和状态 + auto &app = Application::GetInstance(); + auto current_state = app.GetDeviceState(); + + ESP_LOGI(TAG, "当前设备状态: %d", current_state); + + if (current_state == kDeviceStateIdle) { + // 如果当前是待命状态,切换到聆听状态 + ESP_LOGI(TAG, "从待命状态切换到聆听状态"); + app.ToggleChatState(); // 切换到聆听状态 + } else if (current_state == kDeviceStateListening) { + // 如果当前是聆听状态,切换到待命状态 + ESP_LOGI(TAG, "从聆听状态切换到待命状态"); + app.ToggleChatState(); // 切换到待命状态 + } else if (current_state == kDeviceStateSpeaking) { + // 如果当前是说话状态,终止说话并切换到待命状态 + ESP_LOGI(TAG, "从说话状态切换到待命状态"); + app.ToggleChatState(); // 终止说话 + } else { + // 其他状态下只唤醒设备 + ESP_LOGI(TAG, "唤醒设备"); + power_save_timer_->WakeUp(); + } }); + + // 电源键三击:重置WiFi + pwr_button_.OnMultipleClick([this]() + { + ESP_LOGI(TAG, "Power button triple click: 重置WiFi"); + power_save_timer_->WakeUp(); + ResetWifiConfiguration(); }, 3); + + wifi_button.OnPressDown([this]() + { + ESP_LOGI(TAG, "Volume up button pressed"); + power_save_timer_->WakeUp(); + + auto codec = GetAudioCodec(); + int current_vol = codec->output_volume(); // 获取实际当前音量 + current_vol = (current_vol + 8 > 80) ? 80 : current_vol + 8; + + codec->SetOutputVolume(current_vol); + + ESP_LOGI(TAG, "Current volume: %d", current_vol); + int display_volume = MapVolumeForDisplay(current_vol); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(display_volume) + "%");}); + + cmd_button.OnPressDown([this]() + { + ESP_LOGI(TAG, "Volume down button pressed"); + power_save_timer_->WakeUp(); + + auto codec = GetAudioCodec(); + int current_vol = codec->output_volume(); // 获取实际当前音量 + current_vol = (current_vol - 8 < 0) ? 0 : current_vol - 8; + + codec->SetOutputVolume(current_vol); + + ESP_LOGI(TAG, "Current volume: %d", current_vol); + if (current_vol == 0) { + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + } else { + int display_volume = MapVolumeForDisplay(current_vol); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(display_volume) + "%"); + }}); + } + + void InitializeGC9301isplay() + { + // 液晶屏控制IO初始化 + ESP_LOGI(TAG, "test Install panel IO"); + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.sclk_io_num = DISPLAY_SPI_SCK_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + + // 初始化SPI总线 + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io); + + // 初始化液晶屏驱动芯片9309 + ESP_LOGI(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ENDIAN_BGR; + panel_config.bits_per_pixel = 16; + esp_lcd_new_panel_gc9309na(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + JiuchuanDevBoard() : + boot_button_(BOOT_BUTTON_GPIO), + pwr_button_(PWR_BUTTON_GPIO,true), + wifi_button(WIFI_BUTTON_GPIO), + cmd_button(CMD_BUTTON_GPIO) { + + InitializeI2c(); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeButtons(); + InitializeGC9301isplay(); + GetBacklight()->RestoreBrightness(); + + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + + static Es8311AudioCodec audio_codec( + codec_i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(JiuchuanDevBoard); diff --git a/main/boards/jiuchuan-s3/power_controller.h b/main/boards/jiuchuan-s3/power_controller.h new file mode 100644 index 0000000..2496152 --- /dev/null +++ b/main/boards/jiuchuan-s3/power_controller.h @@ -0,0 +1,58 @@ +#pragma once +#include +#include +#include +#include +#include +#include "config.h" +enum class PowerState { + ACTIVE, + LIGHT_SLEEP, + DEEP_SLEEP, + SHUTDOWN + }; + +class PowerController { +public: + + + static PowerController& Instance() { + static PowerController instance; + return instance; + } + + void SetState(PowerState newState) { + std::lock_guard lock(mutex_); + if (currentState_ != newState) { + ESP_LOGI("PowerCtrl", "State change: %d -> %d", + static_cast(currentState_), + static_cast(newState)); + + currentState_ = newState; + if (stateChangeCallback_) { + stateChangeCallback_(newState); + } + } + } + + PowerState GetState() const { + std::lock_guard lock(mutex_); + return currentState_; + } + + void OnStateChange(std::function callback) { + stateChangeCallback_ = callback; + } + +private: + PowerController(){ + rtc_gpio_init(PWR_EN_GPIO); + rtc_gpio_set_direction(PWR_EN_GPIO, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(PWR_EN_GPIO, 1); + } + ~PowerController() = default; + + PowerState currentState_ = PowerState::ACTIVE; + std::function stateChangeCallback_; + mutable std::mutex mutex_; +}; \ No newline at end of file diff --git a/main/boards/jiuchuan-s3/power_manager.h b/main/boards/jiuchuan-s3/power_manager.h new file mode 100644 index 0000000..e306d10 --- /dev/null +++ b/main/boards/jiuchuan-s3/power_manager.h @@ -0,0 +1,201 @@ +#pragma once +#include +#include + +#include +#include +#include "adc_battery_estimation.h" +#include "power_controller.h" +#include +#include + +#define JIUCHUAN_ADC_UNIT (ADC_UNIT_1) +#define JIUCHUAN_ADC_BITWIDTH (ADC_BITWIDTH_12) +#define JIUCHUAN_ADC_ATTEN (ADC_ATTEN_DB_12) +#define JIUCHUAN_ADC_CHANNEL (ADC_CHANNEL_3) +#define JIUCHUAN_RESISTOR_UPPER (200000) +#define JIUCHUAN_RESISTOR_LOWER (100000) + +#undef TAG +#define TAG "PowerManager" +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + int32_t battery_level_ = 100; + bool is_charging_ = false; + bool is_low_battery_ = false; + bool is_empty_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_battery_estimation_handle_t adc_battery_estimation_handle; + PowerController* power_controller_; + + + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + float battery_capacity_temp = 0; + adc_battery_estimation_get_capacity(adc_battery_estimation_handle, &battery_capacity_temp); + ESP_LOGI("PowerManager", "Battery level: %.1f%%", battery_capacity_temp); + if(battery_capacity_temp > -10 && battery_capacity_temp <= 0){ + battery_level_ = 0; + }else{ + battery_level_ = battery_capacity_temp; + } + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + power_controller_ = &PowerController::Instance(); + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + static const battery_point_t battery_ponint_table[]={ + { 4.2 , 100}, + { 4.06 , 80}, + { 3.82 , 60}, + { 3.58 , 40}, + { 3.34 , 20}, + { 3.1 , 0}, + { 3.0 , -10} + }; + + adc_battery_estimation_t config = { + .internal = { + .adc_unit = JIUCHUAN_ADC_UNIT, + .adc_bitwidth = JIUCHUAN_ADC_BITWIDTH, + .adc_atten = JIUCHUAN_ADC_ATTEN, + }, + .adc_channel = JIUCHUAN_ADC_CHANNEL, + .upper_resistor = JIUCHUAN_RESISTOR_UPPER, + .lower_resistor = JIUCHUAN_RESISTOR_LOWER, + .battery_points = battery_ponint_table, + .battery_points_count = sizeof(battery_ponint_table) / sizeof(battery_ponint_table[0]) + }; + + adc_battery_estimation_handle = adc_battery_estimation_create(&config); + + RegisterAllCallbacks(); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_battery_estimation_handle) { + adc_battery_estimation_destroy(adc_battery_estimation_handle); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + //ESP_LOGI(TAG, "电量已满,不再显示充电中"); + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + int32_t GetBatteryLevel() { + return battery_level_; + } + + void RegisterAllCallbacks() { + //注册电源状态变更回调函数(优化版) + power_controller_->OnStateChange([this](PowerState newState) { + switch(newState) { + case PowerState::SHUTDOWN: { + + ESP_LOGD(TAG, "关机"); + + //取消 PWR_EN 使能 + /* 防止关机后误唤醒 */ + ESP_ERROR_CHECK(esp_sleep_enable_ext0_wakeup(PWR_BUTTON_GPIO, 0)); + ESP_ERROR_CHECK(rtc_gpio_pulldown_en(PWR_BUTTON_GPIO)); // 内部下拉 + ESP_ERROR_CHECK(rtc_gpio_pullup_dis(PWR_BUTTON_GPIO)); + /* 关闭电源使能 */ + rtc_gpio_set_level(PWR_EN_GPIO, 0); + rtc_gpio_hold_dis(PWR_EN_GPIO); + + // 确保所有外设已关闭 + vTaskDelay(200 / portTICK_PERIOD_MS); + ESP_LOGI(TAG, "Initiating deep sleep"); + + esp_deep_sleep_start(); + break; + } + default: + ESP_LOGD(TAG, "State changed to %d", static_cast(newState)); + break; + } + }); + } + void SetPowerState(PowerState newState) { + power_controller_->SetState(newState); + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; \ No newline at end of file diff --git a/main/boards/kevin-box-2/config.h b/main/boards/kevin-box-2/config.h new file mode 100644 index 0000000..a272900 --- /dev/null +++ b/main/boards/kevin-box-2/config.h @@ -0,0 +1,41 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_40 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_47 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_48 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_9 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_42 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_41 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_3 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_1 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_2 + +#define DISPLAY_SDA_PIN GPIO_NUM_7 +#define DISPLAY_SCL_PIN GPIO_NUM_8 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define ML307_RX_PIN GPIO_NUM_5 +#define ML307_TX_PIN GPIO_NUM_6 + +#define AXP2101_I2C_ADDR 0x34 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/kevin-box-2/config.json b/main/boards/kevin-box-2/config.json new file mode 100644 index 0000000..d9a581d --- /dev/null +++ b/main/boards/kevin-box-2/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "kevin-box-2", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/kevin-box-2/kevin_box_board.cc b/main/boards/kevin-box-2/kevin_box_board.cc new file mode 100644 index 0000000..94e7e17 --- /dev/null +++ b/main/boards/kevin-box-2/kevin_box_board.cc @@ -0,0 +1,271 @@ +#include "dual_network_board.h" +#include "codecs/box_audio_codec.h" +#include "display/oled_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "KevinBoxBoard" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + // ** EFUSE defaults ** + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + WriteReg(0x93, 0x1C); // 配置 aldo2 输出为 3.3V + + uint8_t value = ReadReg(0x90); // XPOWERS_AXP2101_LDO_ONOFF_CTRL0 + value = value | 0x02; // set bit 1 (ALDO2) + WriteReg(0x90, value); // and power channels now enabled + + WriteReg(0x64, 0x03); // CV charger voltage setting to 4.2V + + WriteReg(0x61, 0x05); // set Main battery precharge current to 125mA + WriteReg(0x62, 0x0A); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x15); // set Main battery term charge current to 125mA + + WriteReg(0x14, 0x00); // set minimum system voltage to 4.1V (default 4.7V), for poor USB cables + WriteReg(0x15, 0x00); // set input voltage limit to 3.88v, for poor USB cables + WriteReg(0x16, 0x05); // set input current limit to 2000mA + + WriteReg(0x24, 0x01); // set Vsys for PWROFF threshold to 3.2V (default - 2.6V and kill battery) + WriteReg(0x50, 0x14); // set TS pin to EXTERNAL input (not temperature) + } +}; + +class KevinBoxBoard : public DualNetworkBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + i2c_master_bus_handle_t codec_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Pmic* pmic_ = nullptr; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, -1, 600); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void Enable4GModule() { + // Make GPIO HIGH to enable the 4G module + gpio_config_t ml307_enable_config = { + .pin_bit_mask = (1ULL << 4), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + gpio_config(&ml307_enable_config); + gpio_set_level(GPIO_NUM_4, 1); + } + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeButtons() { + boot_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + app.StartListening(); + }); + boot_button_.OnPressUp([this]() { + auto& app = Application::GetInstance(); + app.StopListening(); + }); + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + }); + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + +public: + KevinBoxBoard() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeCodecI2c(); + pmic_ = new Pmic(codec_i2c_bus_, AXP2101_I2C_ADDR); + + Enable4GModule(); + + InitializeButtons(); + InitializePowerSaveTimer(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec(codec_i2c_bus_, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR, AUDIO_CODEC_ES7210_ADDR, AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } +}; + +DECLARE_BOARD(KevinBoxBoard); \ No newline at end of file diff --git a/main/boards/kevin-c3/config.h b/main/boards/kevin-c3/config.h new file mode 100644 index 0000000..4241320 --- /dev/null +++ b/main/boards/kevin-c3/config.h @@ -0,0 +1,24 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_13 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_0 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_5 +#define BOOT_BUTTON_GPIO GPIO_NUM_6 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/kevin-c3/config.json b/main/boards/kevin-c3/config.json new file mode 100644 index 0000000..b8bf3b7 --- /dev/null +++ b/main/boards/kevin-c3/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "kevin-c3", + "sdkconfig_append": [ + "CONFIG_ESP_WIFI_ENTERPRISE_SUPPORT=n", + "CONFIG_LWIP_IPV6=n", + "CONFIG_USE_ESP_WAKE_WORD=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/kevin-c3/kevin_c3_board.cc b/main/boards/kevin-c3/kevin_c3_board.cc new file mode 100644 index 0000000..df7e82c --- /dev/null +++ b/main/boards/kevin-c3/kevin_c3_board.cc @@ -0,0 +1,90 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/circular_strip.h" +#include "led_strip_control.h" + +#include +#include +#include +#include + +#define TAG "KevinBoxBoard" + +class KevinBoxBoard : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + CircularStrip* led_strip_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + led_strip_ = new CircularStrip(BUILTIN_LED_GPIO, 8); + new LedStripControl(led_strip_); + } + +public: + KevinBoxBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializeTools(); + + // 把 ESP32C3 的 VDD SPI 引脚作为普通 GPIO 口使用 + esp_efuse_write_field_bit(ESP_EFUSE_VDD_SPI_AS_GPIO); + } + + virtual Led* GetLed() override { + return led_strip_; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } +}; + +DECLARE_BOARD(KevinBoxBoard); diff --git a/main/boards/kevin-c3/led_strip_control.cc b/main/boards/kevin-c3/led_strip_control.cc new file mode 100644 index 0000000..68dc4ae --- /dev/null +++ b/main/boards/kevin-c3/led_strip_control.cc @@ -0,0 +1,129 @@ +#include "led_strip_control.h" +#include "settings.h" +#include "mcp_server.h" +#include + +#define TAG "LedStripControl" + +int LedStripControl::LevelToBrightness(int level) const { + if (level < 0) level = 0; + if (level > 8) level = 8; + return (1 << level) - 1; // 2^n - 1 +} + +StripColor LedStripControl::RGBToColor(int red, int green, int blue) { + if (red < 0) red = 0; + if (red > 255) red = 255; + if (green < 0) green = 0; + if (green > 255) green = 255; + if (blue < 0) blue = 0; + if (blue > 255) blue = 255; + return {static_cast(red), static_cast(green), static_cast(blue)}; +} + +LedStripControl::LedStripControl(CircularStrip* led_strip) + : led_strip_(led_strip) { + // 从设置中读取亮度等级 + Settings settings("led_strip"); + brightness_level_ = settings.GetInt("brightness", 4); // 默认等级4 + led_strip_->SetBrightness(LevelToBrightness(brightness_level_), 4); + + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.led_strip.get_brightness", + "Get the brightness of the led strip (0-8)", + PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return brightness_level_; + }); + + mcp_server.AddTool("self.led_strip.set_brightness", + "Set the brightness of the led strip (0-8)", + PropertyList({ + Property("level", kPropertyTypeInteger, 0, 8) + }), [this](const PropertyList& properties) -> ReturnValue { + int level = properties["level"].value(); + ESP_LOGI(TAG, "Set LedStrip brightness level to %d", level); + brightness_level_ = level; + led_strip_->SetBrightness(LevelToBrightness(brightness_level_), 4); + + // 保存设置 + Settings settings("led_strip", true); + settings.SetInt("brightness", brightness_level_); + + return true; + }); + + mcp_server.AddTool("self.led_strip.set_single_color", + "Set the color of a single led.", + PropertyList({ + Property("index", kPropertyTypeInteger, 0, 7), + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int index = properties["index"].value(); + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + ESP_LOGI(TAG, "Set led strip single color %d to %d, %d, %d", + index, red, green, blue); + led_strip_->SetSingleColor(index, RGBToColor(red, green, blue)); + return true; + }); + + mcp_server.AddTool("self.led_strip.set_all_color", + "Set the color of all leds.", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + ESP_LOGI(TAG, "Set led strip all color to %d, %d, %d", + red, green, blue); + led_strip_->SetAllColor(RGBToColor(red, green, blue)); + return true; + }); + + mcp_server.AddTool("self.led_strip.blink", + "Blink the led strip. (闪烁)", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255), + Property("interval", kPropertyTypeInteger, 0, 1000) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + int interval = properties["interval"].value(); + ESP_LOGI(TAG, "Blink led strip with color %d, %d, %d, interval %dms", + red, green, blue, interval); + led_strip_->Blink(RGBToColor(red, green, blue), interval); + return true; + }); + + mcp_server.AddTool("self.led_strip.scroll", + "Scroll the led strip. (跑马灯)", + PropertyList({ + Property("red", kPropertyTypeInteger, 0, 255), + Property("green", kPropertyTypeInteger, 0, 255), + Property("blue", kPropertyTypeInteger, 0, 255), + Property("length", kPropertyTypeInteger, 1, 7), + Property("interval", kPropertyTypeInteger, 0, 1000) + }), [this](const PropertyList& properties) -> ReturnValue { + int red = properties["red"].value(); + int green = properties["green"].value(); + int blue = properties["blue"].value(); + int interval = properties["interval"].value(); + int length = properties["length"].value(); + ESP_LOGI(TAG, "Scroll led strip with color %d, %d, %d, length %d, interval %dms", + red, green, blue, length, interval); + StripColor low = RGBToColor(4, 4, 4); + StripColor high = RGBToColor(red, green, blue); + led_strip_->Scroll(low, high, length, interval); + return true; + }); + +} diff --git a/main/boards/kevin-c3/led_strip_control.h b/main/boards/kevin-c3/led_strip_control.h new file mode 100644 index 0000000..0e99bb3 --- /dev/null +++ b/main/boards/kevin-c3/led_strip_control.h @@ -0,0 +1,18 @@ +#ifndef LED_STRIP_CONTROL_H +#define LED_STRIP_CONTROL_H + +#include "led/circular_strip.h" + +class LedStripControl { +private: + CircularStrip* led_strip_; + int brightness_level_; // 亮度等级 (0-8) + + int LevelToBrightness(int level) const; // 将等级转换为实际亮度值 + StripColor RGBToColor(int red, int green, int blue); + +public: + explicit LedStripControl(CircularStrip* led_strip); +}; + +#endif // LED_STRIP_CONTROL_H diff --git a/main/boards/kevin-sp-v3-dev/config.h b/main/boards/kevin-sp-v3-dev/config.h new file mode 100644 index 0000000..fd92549 --- /dev/null +++ b/main/boards/kevin-sp-v3-dev/config.h @@ -0,0 +1,64 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_DEFAULT_OUTPUT_VOLUME 90 + + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_42 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_41 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_2 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_3 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_46 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_1 + + +#define BUILTIN_LED_GPIO GPIO_NUM_38 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define RESET_NVS_BUTTON_GPIO GPIO_NUM_NC +#define RESET_FACTORY_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_48 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define ML307_RX_PIN GPIO_NUM_12 +#define ML307_TX_PIN GPIO_NUM_13 +/* Camera pins */ +#define CAMERA_PIN_PWDN -1 +#define CAMERA_PIN_RESET -1 +#define CAMERA_PIN_XCLK 15 +#define CAMERA_PIN_SIOD 4 +#define CAMERA_PIN_SIOC 5 + +#define CAMERA_PIN_D7 16 +#define CAMERA_PIN_D6 17 +#define CAMERA_PIN_D5 18 +#define CAMERA_PIN_D4 12 +#define CAMERA_PIN_D3 10 +#define CAMERA_PIN_D2 8 +#define CAMERA_PIN_D1 9 +#define CAMERA_PIN_D0 11 +#define CAMERA_PIN_VSYNC 6 +#define CAMERA_PIN_HREF 7 +#define CAMERA_PIN_PCLK 13 + +#define XCLK_FREQ_HZ 20000000 +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/kevin-sp-v3-dev/kevin-sp-v3_board.cc b/main/boards/kevin-sp-v3-dev/kevin-sp-v3_board.cc new file mode 100644 index 0000000..11920b5 --- /dev/null +++ b/main/boards/kevin-sp-v3-dev/kevin-sp-v3_board.cc @@ -0,0 +1,165 @@ +#include "wifi_board.h" +#include "ml307_board.h" + +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include "esp32_camera.h" + +#define TAG "kevin-sp-v3" + +// class KEVIN_SP_V3Board : public Ml307Board { +class KEVIN_SP_V3Board : public WifiBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + Esp32Camera* camera_; + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_47; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_21; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_14; + io_config.dc_gpio_num = GPIO_NUM_45; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = CAMERA_PIN_SIOC, + .sda_pin = CAMERA_PIN_SIOD, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + KEVIN_SP_V3Board() : boot_button_(BOOT_BUTTON_GPIO) { + ESP_LOGI(TAG, "Initializing KEVIN_SP_V3 Board"); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + InitializeCamera(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec *GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(KEVIN_SP_V3Board); diff --git a/main/boards/kevin-sp-v4-dev/config.h b/main/boards/kevin-sp-v4-dev/config.h new file mode 100644 index 0000000..27fdc20 --- /dev/null +++ b/main/boards/kevin-sp-v4-dev/config.h @@ -0,0 +1,66 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_42 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_1 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_46 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_2 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_3 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_41 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_4 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_5 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_38 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define RESET_NVS_BUTTON_GPIO GPIO_NUM_NC +#define RESET_FACTORY_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_48 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define ML307_RX_PIN GPIO_NUM_12 +#define ML307_TX_PIN GPIO_NUM_13 +/* Camera pins */ +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_XCLK GPIO_NUM_15 +#define CAMERA_PIN_SIOD GPIO_NUM_4 +#define CAMERA_PIN_SIOC GPIO_NUM_5 + +#define CAMERA_PIN_D7 GPIO_NUM_16 +#define CAMERA_PIN_D6 GPIO_NUM_17 +#define CAMERA_PIN_D5 GPIO_NUM_18 +#define CAMERA_PIN_D4 GPIO_NUM_12 +#define CAMERA_PIN_D3 GPIO_NUM_10 +#define CAMERA_PIN_D2 GPIO_NUM_8 +#define CAMERA_PIN_D1 GPIO_NUM_9 +#define CAMERA_PIN_D0 GPIO_NUM_11 +#define CAMERA_PIN_VSYNC GPIO_NUM_6 +#define CAMERA_PIN_HREF GPIO_NUM_7 +#define CAMERA_PIN_PCLK GPIO_NUM_13 + +#define XCLK_FREQ_HZ 20000000 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/kevin-sp-v4-dev/config.json b/main/boards/kevin-sp-v4-dev/config.json new file mode 100644 index 0000000..1221fbf --- /dev/null +++ b/main/boards/kevin-sp-v4-dev/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "kevin-sp-v4-dev", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/kevin-sp-v4-dev/kevin-sp-v4_board.cc b/main/boards/kevin-sp-v4-dev/kevin-sp-v4_board.cc new file mode 100644 index 0000000..d96fcda --- /dev/null +++ b/main/boards/kevin-sp-v4-dev/kevin-sp-v4_board.cc @@ -0,0 +1,182 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include "esp32_camera.h" + +#define TAG "kevin-sp-v4" + +class KEVIN_SP_V4Board : public WifiBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + i2c_master_bus_handle_t codec_i2c_bus_; + Esp32Camera* camera_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_47; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_21; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_14; + io_config.dc_gpio_num = GPIO_NUM_45; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = CAMERA_PIN_SIOC, + .sda_pin = GPIO_NUM_NC, + }, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + KEVIN_SP_V4Board() : boot_button_(BOOT_BUTTON_GPIO) { + ESP_LOGI(TAG, "Initializing KEVIN SP V4 Board"); + InitializeCodecI2c(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + InitializeCamera(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(KEVIN_SP_V4Board); diff --git a/main/boards/kevin-yuying-313lcd/config.h b/main/boards/kevin-yuying-313lcd/config.h new file mode 100644 index 0000000..b533741 --- /dev/null +++ b/main/boards/kevin-yuying-313lcd/config.h @@ -0,0 +1,35 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 16000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_42 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_39 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_41 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_38 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_45 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_1 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_2 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_WIDTH 376 +#define DISPLAY_HEIGHT 960 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_4 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/kevin-yuying-313lcd/config.json b/main/boards/kevin-yuying-313lcd/config.json new file mode 100644 index 0000000..ae29bb4 --- /dev/null +++ b/main/boards/kevin-yuying-313lcd/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "kevin-yuying-313lcd", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.c b/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.c new file mode 100644 index 0000000..9f62738 --- /dev/null +++ b/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.c @@ -0,0 +1,478 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "esp_lcd_gc9503.h" + +#define GC9503_CMD_MADCTL (0xB1) // Memory data access control +#define GC9503_CMD_MADCTL_DEFAULT (0x10) // Default value of Memory data access control +#define GC9503_CMD_SS_BIT (1 << 0) // Source driver scan direction, 0: top to bottom, 1: bottom to top +#define GC9503_CMD_GS_BIT (1 << 1) // Gate driver scan direction, 0: left to right, 1: right to left +#define GC9503_CMD_BGR_BIT (1 << 5) // RGB/BGR order, 0: RGB, 1: BGR + +typedef struct +{ + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // Save current value of GC9503_CMD_MADCTL register + uint8_t colmod_val; // Save current value of LCD_CMD_COLMOD register + const gc9503_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + struct + { + unsigned int mirror_by_cmd : 1; + unsigned int auto_del_panel_io : 1; + unsigned int display_on_off_use_cmd : 1; + unsigned int reset_level : 1; + } flags; + // To save the original functions of RGB panel + esp_err_t (*init)(esp_lcd_panel_t *panel); + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*reset)(esp_lcd_panel_t *panel); + esp_err_t (*mirror)(esp_lcd_panel_t *panel, bool x_axis, bool y_axis); + esp_err_t (*disp_on_off)(esp_lcd_panel_t *panel, bool on_off); +} gc9503_panel_t; + +static const char *TAG = "gc9503"; + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503); + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool off); + +esp_err_t esp_lcd_new_panel_gc9503(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + gc9503_vendor_config_t *vendor_config = (gc9503_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->rgb_config, ESP_ERR_INVALID_ARG, TAG, "`verndor_config` and `rgb_config` are necessary"); + ESP_RETURN_ON_FALSE(!vendor_config->flags.auto_del_panel_io || !vendor_config->flags.mirror_by_cmd, + ESP_ERR_INVALID_ARG, TAG, "`mirror_by_cmd` and `auto_del_panel_io` cannot work together"); + + esp_err_t ret = ESP_OK; + gpio_config_t io_conf = {0}; + + gc9503_panel_t *gc9503 = (gc9503_panel_t *)calloc(1, sizeof(gc9503_panel_t)); + ESP_RETURN_ON_FALSE(gc9503, ESP_ERR_NO_MEM, TAG, "no mem for gc9503 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + gc9503->madctl_val = GC9503_CMD_MADCTL_DEFAULT; + switch (panel_dev_config->rgb_ele_order) + { + case LCD_RGB_ELEMENT_ORDER_RGB: + gc9503->madctl_val &= ~GC9503_CMD_BGR_BIT; + break; + case LCD_RGB_ELEMENT_ORDER_BGR: + gc9503->madctl_val |= GC9503_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color element order"); + break; + } + + gc9503->colmod_val = 0; + switch (panel_dev_config->bits_per_pixel) + { + case 16: // RGB565 + gc9503->colmod_val = 0x50; + break; + case 18: // RGB666 + gc9503->colmod_val = 0x60; + break; + case 24: // RGB888 + gc9503->colmod_val = 0x70; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + gc9503->io = io; + gc9503->init_cmds = vendor_config->init_cmds; + gc9503->init_cmds_size = vendor_config->init_cmds_size; + gc9503->reset_gpio_num = panel_dev_config->reset_gpio_num; + gc9503->flags.reset_level = panel_dev_config->flags.reset_active_high; + gc9503->flags.auto_del_panel_io = vendor_config->flags.auto_del_panel_io; + gc9503->flags.mirror_by_cmd = vendor_config->flags.mirror_by_cmd; + gc9503->flags.display_on_off_use_cmd = (vendor_config->rgb_config->disp_gpio_num >= 0) ? 0 : 1; + + if (gc9503->flags.auto_del_panel_io) + { + if (gc9503->reset_gpio_num >= 0) + { // Perform hardware reset + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + } + else + { // Perform software reset + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), err, TAG, "send command failed"); + } + vTaskDelay(pdMS_TO_TICKS(120)); + + /** + * In order to enable the 3-wire SPI interface pins (such as SDA and SCK) to share other pins of the RGB interface + * (such as HSYNC) and save GPIOs, we need to send LCD initialization commands via the 3-wire SPI interface before + * `esp_lcd_new_rgb_panel()` is called. + */ + ESP_GOTO_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), err, TAG, "send init commands failed"); + // After sending the initialization commands, the 3-wire SPI interface can be deleted + ESP_GOTO_ON_ERROR(esp_lcd_panel_io_del(io), err, TAG, "delete panel IO failed"); + gc9503->io = NULL; + ESP_LOGD(TAG, "delete panel IO"); + } + + // Create RGB panel + ESP_GOTO_ON_ERROR(esp_lcd_new_rgb_panel(vendor_config->rgb_config, ret_panel), err, TAG, "create RGB panel failed"); + ESP_LOGD(TAG, "new RGB panel @%p", ret_panel); + + // Save the original functions of RGB panel + gc9503->init = (*ret_panel)->init; + gc9503->del = (*ret_panel)->del; + gc9503->reset = (*ret_panel)->reset; + gc9503->mirror = (*ret_panel)->mirror; + gc9503->disp_on_off = (*ret_panel)->disp_on_off; + // Overwrite the functions of RGB panel + (*ret_panel)->init = panel_gc9503_init; + (*ret_panel)->del = panel_gc9503_del; + (*ret_panel)->reset = panel_gc9503_reset; + (*ret_panel)->mirror = panel_gc9503_mirror; + (*ret_panel)->disp_on_off = panel_gc9503_disp_on_off; + (*ret_panel)->user_data = gc9503; + ESP_LOGD(TAG, "new gc9503 panel @%p", gc9503); + + // ESP_LOGI(TAG, "LCD panel create success, version: %d.%d.%d", ESP_LCD_GC9503_VER_MAJOR, ESP_LCD_GC9503_VER_MINOR, + // ESP_LCD_GC9503_VER_PATCH); + return ESP_OK; + +err: + if (gc9503) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(gc9503); + } + return ret; +} + +// *INDENT-OFF* +// static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { +// // {cmd, { data }, data_size, delay_ms} +// {0x11, (uint8_t []){0x00}, 0, 120}, + +// {0xf0, (uint8_t []){0x55, 0xaa, 0x52, 0x08, 0x00}, 5, 0}, +// {0xf6, (uint8_t []){0x5a, 0x87}, 2, 0}, +// {0xc1, (uint8_t []){0x3f}, 1, 0}, +// {0xc2, (uint8_t []){0x0e}, 1, 0}, +// {0xc6, (uint8_t []){0xf8}, 1, 0}, +// {0xc9, (uint8_t []){0x10}, 1, 0}, +// {0xcd, (uint8_t []){0x25}, 1, 0}, +// {0xf8, (uint8_t []){0x8a}, 1, 0}, +// {0xac, (uint8_t []){0x45}, 1, 0}, +// {0xa0, (uint8_t []){0xdd}, 1, 0}, +// {0xa7, (uint8_t []){0x47}, 1, 0}, +// {0xfa, (uint8_t []){0x00, 0x00, 0x00, 0x04}, 4, 0}, +// {0x86, (uint8_t []){0x99, 0xa3, 0xa3, 0x51}, 4, 0}, +// {0xa3, (uint8_t []){0xee}, 1, 0}, +// {0xfd, (uint8_t []){0x3c, 0x3c, 0x00}, 3, 0}, +// {0x71, (uint8_t []){0x48}, 1, 0}, +// {0x72, (uint8_t []){0x48}, 1, 0}, +// {0x73, (uint8_t []){0x00, 0x44}, 2, 0}, +// {0x97, (uint8_t []){0xee}, 1, 0}, +// {0x83, (uint8_t []){0x93}, 1, 0}, +// {0x9a, (uint8_t []){0x72}, 1, 0}, +// {0x9b, (uint8_t []){0x5a}, 1, 0}, +// {0x82, (uint8_t []){0x2c, 0x2c}, 2, 0}, +// {0x6d, (uint8_t []){0x00, 0x1f, 0x19, 0x1a, 0x10, 0x0e, 0x0c, 0x0a, 0x02, 0x07, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, +// 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x08, 0x01, 0x09, 0x0b, 0x0d, 0x0f, 0x1a, 0x19, 0x1f, 0x00}, 32, 0}, +// {0x64, (uint8_t []){0x38, 0x05, 0x01, 0xdb, 0x03, 0x03, 0x38, 0x04, 0x01, 0xdc, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x65, (uint8_t []){0x38, 0x03, 0x01, 0xdd, 0x03, 0x03, 0x38, 0x02, 0x01, 0xde, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x66, (uint8_t []){0x38, 0x01, 0x01, 0xdf, 0x03, 0x03, 0x38, 0x00, 0x01, 0xe0, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x67, (uint8_t []){0x30, 0x01, 0x01, 0xe1, 0x03, 0x03, 0x30, 0x02, 0x01, 0xe2, 0x03, 0x03, 0x7a, 0x7a, 0x7a, 0x7a}, 16, 0}, +// {0x68, (uint8_t []){0x00, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a, 0x08, 0x15, 0x08, 0x15, 0x7a, 0x7a}, 13, 0}, +// {0x60, (uint8_t []){0x38, 0x08, 0x7a, 0x7a, 0x38, 0x09, 0x7a, 0x7a}, 8, 0}, +// {0x63, (uint8_t []){0x31, 0xe4, 0x7a, 0x7a, 0x31, 0xe5, 0x7a, 0x7a}, 8, 0}, +// {0x69, (uint8_t []){0x04, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, +// {0x6b, (uint8_t []){0x07}, 1, 0}, +// {0x7a, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0x7b, (uint8_t []){0x08, 0x13}, 2, 0}, +// {0xd1, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd2, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd3, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd4, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd5, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0xd6, (uint8_t []){0x00, 0x00, 0x00, 0x04, 0x00, 0x12, 0x00, 0x18, 0x00, 0x21, 0x00, 0x2a, 0x00, 0x35, 0x00, 0x47, 0x00, +// 0x56, 0x00, 0x90, 0x00, 0xe5, 0x01, 0x68, 0x01, 0xd5, 0x01, 0xd7, 0x02, 0x36, 0x02, 0xa6, 0x02, 0xee, +// 0x03, 0x48, 0x03, 0xa0, 0x03, 0xba, 0x03, 0xc5, 0x03, 0xd0, 0x03, 0xe0, 0x03, 0xea, 0x03, 0xfa, 0x03, +// 0xff}, 52, 0}, +// {0x11, (uint8_t []){0x00}, 0, 120}, +// {0x29, (uint8_t []){0x00}, 0, 20}, +// }; +static const gc9503_lcd_init_cmd_t vendor_specific_init_default[] = { + // {0x11, (uint8_t[]){}, 0, 20}, + + {0xF0, (uint8_t[]){0x55, 0xAA, 0x52, 0x08, 0x00}, 5, 0}, + {0xF6, (uint8_t[]){0x5A, 0x87}, 2, 0}, + {0xC1, (uint8_t[]){0x3F}, 1, 0}, + {0xCD, (uint8_t[]){0x25}, 1, 0}, + {0xC9, (uint8_t[]){0x10}, 1, 0}, + {0xF8, (uint8_t[]){0x8A}, 1, 0}, + {0xAC, (uint8_t[]){0x45}, 1, 0}, + {0xA7, (uint8_t[]){0x47}, 1, 0}, + {0xA0, (uint8_t[]){0x88}, 1, 0}, + {0x86, (uint8_t[]){0x99, 0xA3, 0xA3, 0x51}, 4, 0}, + {0xFA, (uint8_t[]){0x08, 0x08, 0x00, 0x04}, 4, 0}, + {0xA3, (uint8_t[]){0x6E}, 1, 0}, + {0xFD, (uint8_t[]){0x28, 0x3C, 0x00}, 3, 0}, + {0x9A, (uint8_t[]){0x4B}, 1, 0}, + {0x9B, (uint8_t[]){0x4B}, 1, 0}, + {0x82, (uint8_t[]){0x20, 0x20}, 2, 0}, + {0xB1, (uint8_t[]){0x10}, 1, 0}, + {0x7A, (uint8_t[]){0x0F, 0x13}, 2, 0}, + {0x7B, (uint8_t[]){0x0F, 0x13}, 2, 0}, + {0x6D, (uint8_t[]){0x1e, 0x1e, 0x04, 0x02, 0x0d, 0x1e, 0x12, 0x11, 0x14, 0x13, 0x05, 0x06, 0x1d, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1e, 0x1d, 0x06, 0x05, 0x0b, 0x0c, 0x09, 0x0a, 0x1e, 0x0d, 0x01, 0x03, 0x1e, 0x1e}, 32, 0}, + {0x64, (uint8_t[]){0x38, 0x08, 0x03, 0xc0, 0x03, 0x03, 0x38, 0x06, 0x03, 0xc2, 0x03, 0x03, 0x20, 0x6d, 0x20, 0x6d}, 16, 0}, + {0x65, (uint8_t[]){0x38, 0x04, 0x03, 0xc4, 0x03, 0x03, 0x38, 0x02, 0x03, 0xc6, 0x03, 0x03, 0x20, 0x6d, 0x20, 0x6d}, 16, 0}, + {0x66, (uint8_t[]){0x83, 0xcf, 0x03, 0xc8, 0x03, 0x03, 0x83, 0xd3, 0x03, 0xd2, 0x03, 0x03, 0x20, 0x6d, 0x20, 0x6d}, 16, 0}, + {0x60, (uint8_t[]){0x38, 0x0C, 0x20, 0x6D, 0x38, 0x0B, 0x20, 0x6D}, 8, 0}, + {0x61, (uint8_t[]){0x38, 0x0A, 0x20, 0x6D, 0x38, 0x09, 0x20, 0x6D}, 8, 0}, + {0x62, (uint8_t[]){0x38, 0x25, 0x20, 0x6D, 0x63, 0xC9, 0x20, 0x6D}, 8, 0}, + {0x69, (uint8_t[]){0x14, 0x22, 0x14, 0x22, 0x14, 0x22, 0x08}, 7, 0}, + {0x6B, (uint8_t[]){0x07}, 1, 0}, + {0xD1, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + {0xD2, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + {0xD3, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + {0xD4, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + {0xD5, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + {0xD6, (uint8_t[]){0x00, 0x00, 0x00, 0x70, 0x00, 0x8f, 0x00, 0xab, 0x00, 0xbf, 0x00, 0xdf, 0x00, 0xfa, 0x01, 0x2a, 0x01, 0x52, 0x01, 0x90, 0x01, 0xc1, 0x02, 0x0e, 0x02, 0x4f, 0x02, 0x51, 0x02, 0x8d, 0x02, 0xd3, 0x02, 0xff, 0x03, 0x3c, 0x03, 0x64, 0x03, 0xa1, 0x03, 0xf1, 0x03, 0xff, 0x03, 0xfF, 0x03, 0xff, 0x03, 0xFf, 0x03, 0xFF}, 52, 0}, + // {0x3A, (uint8_t[]){0x55}, 1, 0}, + + {0x11, NULL, 0, 120}, // Delay 120ms + {0x29, NULL, 0, 120}}; + +// *INDENT-OFF* + +static esp_err_t panel_gc9503_send_init_cmds(gc9503_panel_t *gc9503) +{ + esp_lcd_panel_io_handle_t io = gc9503->io; + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]){ + gc9503->colmod_val, + }, + 1), + TAG, "send command failed"); + ; + + // Vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + const gc9503_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + if (gc9503->init_cmds) + { + init_cmds = gc9503->init_cmds; + init_cmds_size = gc9503->init_cmds_size; + } + else + { + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(gc9503_lcd_init_cmd_t); + } + + bool is_cmd_overwritten = false; + for (int i = 0; i < init_cmds_size; i++) + { + // Check if the command has been used or conflicts with the internal + switch (init_cmds[i].cmd) + { + case LCD_CMD_MADCTL: + is_cmd_overwritten = true; + gc9503->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + case LCD_CMD_COLMOD: + is_cmd_overwritten = true; + gc9503->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + default: + is_cmd_overwritten = false; + break; + } + + if (is_cmd_overwritten) + { + ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + init_cmds[i].cmd); + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), + TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + } + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_init(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (!gc9503->flags.auto_del_panel_io) + { + ESP_RETURN_ON_ERROR(panel_gc9503_send_init_cmds(gc9503), TAG, "send init commands failed"); + } + // Init RGB panel + ESP_RETURN_ON_ERROR(gc9503->init(panel), TAG, "init RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_del(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + + if (gc9503->reset_gpio_num >= 0) + { + gpio_reset_pin(gc9503->reset_gpio_num); + } + // Delete RGB panel + gc9503->del(panel); + free(gc9503); + ESP_LOGD(TAG, "del gc9503 panel @%p", gc9503); + return ESP_OK; +} + +static esp_err_t panel_gc9503_reset(esp_lcd_panel_t *panel) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + // Perform hardware reset + if (gc9503->reset_gpio_num >= 0) + { + gpio_set_level(gc9503->reset_gpio_num, gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9503->reset_gpio_num, !gc9503->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(120)); + } + else if (io) + { // Perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(120)); + } + // Reset RGB panel + ESP_RETURN_ON_ERROR(gc9503->reset(panel), TAG, "reset RGB panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9503_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + + if (gc9503->flags.mirror_by_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control mirror through LCD command + if (mirror_x) + { + gc9503->madctl_val |= GC9503_CMD_GS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_GS_BIT; + } + if (mirror_y) + { + gc9503->madctl_val |= GC9503_CMD_SS_BIT; + } + else + { + gc9503->madctl_val &= ~GC9503_CMD_SS_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, GC9503_CMD_MADCTL, (uint8_t[]){ + gc9503->madctl_val, + }, + 1), + TAG, "send command failed"); + ; + } + else + { + // Control mirror through RGB panel + ESP_RETURN_ON_ERROR(gc9503->mirror(panel, mirror_x, mirror_y), TAG, "RGB panel mirror failed"); + } + return ESP_OK; +} + +static esp_err_t panel_gc9503_disp_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + gc9503_panel_t *gc9503 = (gc9503_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = gc9503->io; + int command = 0; + + if (gc9503->flags.display_on_off_use_cmd) + { + ESP_RETURN_ON_FALSE(io, ESP_FAIL, TAG, "Panel IO is deleted, cannot send command"); + // Control display on/off through LCD command + if (on_off) + { + command = LCD_CMD_DISPON; + } + else + { + command = LCD_CMD_DISPOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + } + else + { + // Control display on/off through display control signal + ESP_RETURN_ON_ERROR(gc9503->disp_on_off(panel, on_off), TAG, "RGB panel disp_on_off failed"); + } + return ESP_OK; +} diff --git a/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.h b/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.h new file mode 100644 index 0000000..40a5ccc --- /dev/null +++ b/main/boards/kevin-yuying-313lcd/esp_lcd_gc9503.h @@ -0,0 +1,145 @@ +/* + * SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * @file + * @brief ESP LCD: GC9503 + */ + +#pragma once + +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct { + int cmd; /* +#include +#include +#include "esp_lcd_gc9503.h" +#include +#include +#include + +#define TAG "Yuying_313lcd" + +class Yuying_313lcd : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + void InitializeRGB_GC9503V_Display() { + ESP_LOGI(TAG, "Init GC9503V"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + + ESP_LOGI(TAG, "Install 3-wire SPI panel IO"); + spi_line_config_t line_config = { + .cs_io_type = IO_TYPE_GPIO, + .cs_gpio_num = GC9503V_LCD_IO_SPI_CS_1, + .scl_io_type = IO_TYPE_GPIO, + .scl_gpio_num = GC9503V_LCD_IO_SPI_SCL_1, + .sda_io_type = IO_TYPE_GPIO, + .sda_gpio_num = GC9503V_LCD_IO_SPI_SDO_1, + .io_expander = NULL, + }; + esp_lcd_panel_io_3wire_spi_config_t io_config = GC9503_PANEL_IO_3WIRE_SPI_CONFIG(line_config, 0); + (esp_lcd_new_panel_io_3wire_spi(&io_config, &panel_io)); + + ESP_LOGI(TAG, "Install RGB LCD panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_rgb_panel_config_t rgb_config = { + .clk_src = LCD_CLK_SRC_PLL160M, + .timings = GC9503_376_960_PANEL_60HZ_RGB_TIMING(), + .data_width = 16, // RGB565 in parallel mode, thus 16bit in width + .bits_per_pixel = 16, + .num_fbs = GC9503V_LCD_RGB_BUFFER_NUMS, + .bounce_buffer_size_px = GC9503V_LCD_H_RES * GC9503V_LCD_RGB_BOUNCE_BUFFER_HEIGHT, + .dma_burst_size = 64, + .hsync_gpio_num = GC9503V_PIN_NUM_HSYNC, + .vsync_gpio_num = GC9503V_PIN_NUM_VSYNC, + .de_gpio_num = GC9503V_PIN_NUM_DE, + .pclk_gpio_num = GC9503V_PIN_NUM_PCLK, + .disp_gpio_num = GC9503V_PIN_NUM_DISP_EN, + .data_gpio_nums = { + GC9503V_PIN_NUM_DATA0, + GC9503V_PIN_NUM_DATA1, + GC9503V_PIN_NUM_DATA2, + GC9503V_PIN_NUM_DATA3, + GC9503V_PIN_NUM_DATA4, + GC9503V_PIN_NUM_DATA5, + GC9503V_PIN_NUM_DATA6, + GC9503V_PIN_NUM_DATA7, + GC9503V_PIN_NUM_DATA8, + GC9503V_PIN_NUM_DATA9, + GC9503V_PIN_NUM_DATA10, + GC9503V_PIN_NUM_DATA11, + GC9503V_PIN_NUM_DATA12, + GC9503V_PIN_NUM_DATA13, + GC9503V_PIN_NUM_DATA14, + GC9503V_PIN_NUM_DATA15, + }, + .flags= { + .fb_in_psram = true, // allocate frame buffer in PSRAM + } + }; + + ESP_LOGI(TAG, "Initialize RGB LCD panel"); + + gc9503_vendor_config_t vendor_config = { + .rgb_config = &rgb_config, + .flags = { + .mirror_by_cmd = 0, + .auto_del_panel_io = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = -1, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = &vendor_config, + }; + (esp_lcd_new_panel_gc9503(panel_io, &panel_config, &panel_handle)); + (esp_lcd_panel_reset(panel_handle)); + (esp_lcd_panel_init(panel_handle)); + + display_ = new RgbLcdDisplay(panel_io, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + +public: + Yuying_313lcd() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializeRGB_GC9503V_Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(Yuying_313lcd); diff --git a/main/boards/kevin-yuying-313lcd/pin_config.h b/main/boards/kevin-yuying-313lcd/pin_config.h new file mode 100644 index 0000000..0bcd059 --- /dev/null +++ b/main/boards/kevin-yuying-313lcd/pin_config.h @@ -0,0 +1,47 @@ + +#pragma once +#define GC9503V_LCD_H_RES 376 +#define GC9503V_LCD_V_RES 960 + + +#define GC9503V_LCD_LVGL_DIRECT_MODE (1) +#define GC9503V_LCD_LVGL_AVOID_TEAR (1) +#define GC9503V_LCD_RGB_BOUNCE_BUFFER_MODE (1) +#define GC9503V_LCD_DRAW_BUFF_DOUBLE (0) +#define GC9503V_LCD_DRAW_BUFF_HEIGHT (100) +#define GC9503V_LCD_RGB_BUFFER_NUMS (2) +#define GC9503V_LCD_RGB_BOUNCE_BUFFER_HEIGHT (10) + +#define GC9503V_LCD_PIXEL_CLOCK_HZ (16 * 1000 * 1000) +#define GC9503V_LCD_BK_LIGHT_ON_LEVEL 1 +#define GC9503V_LCD_BK_LIGHT_OFF_LEVEL !GC9503V_LCD_BK_LIGHT_ON_LEVEL +#define GC9503V_PIN_NUM_BK_LIGHT GPIO_NUM_4 +#define GC9503V_PIN_NUM_HSYNC 6 +#define GC9503V_PIN_NUM_VSYNC 5 +#define GC9503V_PIN_NUM_DE 15 +#define GC9503V_PIN_NUM_PCLK 7 + +#define GC9503V_PIN_NUM_DATA0 47 // B0 +#define GC9503V_PIN_NUM_DATA1 21 // B1 +#define GC9503V_PIN_NUM_DATA2 14 // B2 +#define GC9503V_PIN_NUM_DATA3 13 // B3 +#define GC9503V_PIN_NUM_DATA4 12 // B4 + +#define GC9503V_PIN_NUM_DATA5 11 // G0 +#define GC9503V_PIN_NUM_DATA6 10 // G1 +#define GC9503V_PIN_NUM_DATA7 9 // G2 +#define GC9503V_PIN_NUM_DATA8 46 // G3 +#define GC9503V_PIN_NUM_DATA9 3 // G4 +#define GC9503V_PIN_NUM_DATA10 20 // G5 + +#define GC9503V_PIN_NUM_DATA11 19 // R0 +#define GC9503V_PIN_NUM_DATA12 8 // R1 +#define GC9503V_PIN_NUM_DATA13 18 // R2 +#define GC9503V_PIN_NUM_DATA14 17 // R3 +#define GC9503V_PIN_NUM_DATA15 16 // R4 + +#define GC9503V_PIN_NUM_DISP_EN -1 + +#define GC9503V_LCD_IO_SPI_CS_1 (GPIO_NUM_48) +#define GC9503V_LCD_IO_SPI_SCL_1 (GPIO_NUM_17) +#define GC9503V_LCD_IO_SPI_SDO_1 (GPIO_NUM_16) \ No newline at end of file diff --git a/main/boards/labplus-ledong-v2/README.md b/main/boards/labplus-ledong-v2/README.md new file mode 100644 index 0000000..3be2b94 --- /dev/null +++ b/main/boards/labplus-ledong-v2/README.md @@ -0,0 +1,62 @@ +# labplus 乐动掌控V2 + +## 板载资源 + 主控:ESP32-S3 外挂8MB psram 16MB flash + 传感器: + 按钮(A B按键) IO0 IO46 + 光照传感器 IIC + 6轴 IIC + 磁力计 IIC + 声音触发 IO6 + 触摸按键 IIC P Y T H O N + 摄像头 IIC + 执行器: + 蜂鸣器 IO21 + RGB灯 IO16 + 录音播放 es8388 IIC + TFT LCD jd9853 SPI + 电机驱动 IIC + + +## 编译配置 + +### 配置编译目标为 ESP32S3,USB JTAG下载 + +```bash +idf.py set-target esp32s3 +``` + +### menuconfig配置 + +```bash +idf.py menuconfig +``` + +***选择板子:*** + +``` +Xiaozhi Assistant -> Board Type -> labplus Ledong_v2 board +``` + +***修改 psram 配置:*** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> quad Mode PSRAM +``` + +**编译:** + +```bash +idf.py build +``` + +**固件打包:** + +```bash +esptool.py -p /dev/ttyACM0 -b 1500000 --before default_reset --after hard_reset --chip esp32s3 write_flash --flash_mode dio --flash_freq 80m --flash_size 16MB 0x0 bootloader/bootloader.bin 0x100000 xiaozhi.bin 0x8000 partition_table/partition-table.bin 0xd000 ota_data_initial.bin 0x10000 srmodels/srmodels.bin +``` + +## 使用 + +### 按键配置 +* A:短按-打断/唤醒 diff --git a/main/boards/labplus-ledong-v2/config.h b/main/boards/labplus-ledong-v2/config.h new file mode 100644 index 0000000..79f9d4f --- /dev/null +++ b/main/boards/labplus-ledong-v2/config.h @@ -0,0 +1,44 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_39 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_42 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_41 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_38 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_44 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_43 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BUILTIN_LED_GPIO GPIO_NUM_1 + +#define LCD_SCLK_PIN GPIO_NUM_36 +#define LCD_MOSI_PIN GPIO_NUM_37 +#define LCD_MISO_PIN GPIO_NUM_NC +#define LCD_DC_PIN GPIO_NUM_35 +#define LCD_CS_PIN GPIO_NUM_NC + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 172 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 34 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_34 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/labplus-ledong-v2/config.json b/main/boards/labplus-ledong-v2/config.json new file mode 100644 index 0000000..8df7030 --- /dev/null +++ b/main/boards/labplus-ledong-v2/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "labplus-ledong-v2", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/labplus-ledong-v2/labplus_ledong_v2.cc b/main/boards/labplus-ledong-v2/labplus_ledong_v2.cc new file mode 100644 index 0000000..e1f7d88 --- /dev/null +++ b/main/boards/labplus-ledong-v2/labplus_ledong_v2.cc @@ -0,0 +1,163 @@ +#include "wifi_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include + +#define TAG "labplus_ledong_v2" + +#define BOARD_STM8_ADDR 17 +#define BOARD_STM8_CMD 4 + +class labplus_ledong_v2 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeJd9853Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + ESP_LOGD(TAG, "Install panel IO"); + // 液晶屏控制IO初始化 + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 20 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io); + + // 初始化液晶屏驱动芯片JD9853,使用ST7789驱动,时序和复位有调整。 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG, + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel); + + #if CONFIG_BOARD_TYPE_LABPLUS_LEDONG_V2 + ESP_LOGI(TAG, "Reset LCD."); + i2c_device_config_t dev_cfg = { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = BOARD_STM8_ADDR, + .scl_speed_hz = 400000, + }; + + i2c_master_dev_handle_t dev_handle; + i2c_master_bus_add_device(i2c_bus_, &dev_cfg, &dev_handle); + + uint8_t reg = BOARD_STM8_CMD; + i2c_master_transmit(dev_handle, ®, 1, -1); + + i2c_master_bus_rm_device(dev_handle); + #endif + + esp_lcd_panel_reset(panel); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + labplus_ledong_v2() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeJd9853Display(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8388_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(labplus_ledong_v2); diff --git a/main/boards/labplus-mpython-v3/README.md b/main/boards/labplus-mpython-v3/README.md new file mode 100644 index 0000000..c5a4845 --- /dev/null +++ b/main/boards/labplus-mpython-v3/README.md @@ -0,0 +1,61 @@ +# labplus 掌控板V3 + +## 板载资源 + 主控:ESP32-S3 外挂8MB psram 16MB flash + 传感器: + 按钮(A B按键) IO0 IO46 + 光照传感器 IIC + 6轴 IIC + 磁力计 IIC + 声音触发 IO6 + 触摸按键 P Y T H O N + 摄像头 IIC + 执行器: + 蜂鸣器 IO21 + RGB灯 IO16 + 录音播放 es8388 IIC + TFT LCD jd9853 SPI + + +## 编译配置 + +### 配置编译目标为 ESP32S3,USB JTAG下载 + +```bash +idf.py set-target esp32s3 +``` + +### menuconfig配置 + +```bash +idf.py menuconfig +``` + +***选择板子:*** + +``` +Xiaozhi Assistant -> Board Type -> labplus mpython_v3 board +``` + +***修改 psram 配置:*** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> quad Mode PSRAM +``` + +**编译:** + +```bash +idf.py build +``` + +**固件打包:** + +```bash +esptool.py -p /dev/ttyACM0 -b 1500000 --before default_reset --after hard_reset --chip esp32s3 write_flash --flash_mode dio --flash_freq 80m --flash_size 16MB 0x0 bootloader/bootloader.bin 0x100000 xiaozhi.bin 0x8000 partition_table/partition-table.bin 0xd000 ota_data_initial.bin 0x10000 srmodels/srmodels.bin +``` + +## 使用 + +### 按键配置 +* A:短按-打断/唤醒 diff --git a/main/boards/labplus-mpython-v3/config.h b/main/boards/labplus-mpython-v3/config.h new file mode 100644 index 0000000..e6a8484 --- /dev/null +++ b/main/boards/labplus-mpython-v3/config.h @@ -0,0 +1,44 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_39 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_42 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_41 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_38 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_44 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_43 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BUILTIN_LED_GPIO GPIO_NUM_1 + +#define LCD_SCLK_PIN GPIO_NUM_36 +#define LCD_MOSI_PIN GPIO_NUM_37 +#define LCD_MISO_PIN GPIO_NUM_NC +#define LCD_DC_PIN GPIO_NUM_35 +#define LCD_CS_PIN GPIO_NUM_34 + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 172 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 34 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_33 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ + diff --git a/main/boards/labplus-mpython-v3/config.json b/main/boards/labplus-mpython-v3/config.json new file mode 100644 index 0000000..b5bd0ee --- /dev/null +++ b/main/boards/labplus-mpython-v3/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "labplus-mpython-v3", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/labplus-mpython-v3/mpython_pro.cc b/main/boards/labplus-mpython-v3/mpython_pro.cc new file mode 100644 index 0000000..3b9d149 --- /dev/null +++ b/main/boards/labplus-mpython-v3/mpython_pro.cc @@ -0,0 +1,143 @@ +#include "wifi_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/single_led.h" + +#include +#include +#include +#include +#include + +#define TAG "mpython_v3" + +class mpython_v3 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + // Initialize spi peripheral + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = LCD_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = LCD_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + ESP_LOGD(TAG, "Install panel IO"); + // 液晶屏控制IO初始化 + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS_PIN; + io_config.dc_gpio_num = LCD_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 20 * 1000 * 1000; + io_config.trans_queue_depth = 7; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io); + + // 初始化液晶屏驱动芯片JD9853,使用ST7789驱动,时序有调整。 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.data_endian = LCD_RGB_DATA_ENDIAN_BIG, + esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + vTaskDelay(pdMS_TO_TICKS(100)); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + mpython_v3() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8388_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(mpython_v3); diff --git a/main/boards/lichuang-c3-dev/README.md b/main/boards/lichuang-c3-dev/README.md new file mode 100644 index 0000000..ec6ec88 --- /dev/null +++ b/main/boards/lichuang-c3-dev/README.md @@ -0,0 +1,11 @@ +## 立创·实战派ESP32-C3开发板 + +1、开发板资料:https://wiki.lckfb.com/zh-hans/szpi-esp32c3 + +2、该开发板 flash 大小为 8MB,编译时注意选择合适的分区表: + +``` +Partition Table ---> + Partition Table (Custom partition table CSV) ---> + (partitions/v2/8m.csv) Custom partition CSV file +``` diff --git a/main/boards/lichuang-c3-dev/config.h b/main/boards/lichuang-c3-dev/config.h new file mode 100644 index 0000000..548ccb4 --- /dev/null +++ b/main/boards/lichuang-c3-dev/config.h @@ -0,0 +1,45 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 + +#define AUDIO_CODEC_USE_PCA9557 +#define AUDIO_CODEC_PA_PIN GPIO_NUM_13 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_0 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR 0x82 + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_9 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SPI_SCK_PIN GPIO_NUM_3 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_6 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_4 + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_2 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lichuang-c3-dev/config.json b/main/boards/lichuang-c3-dev/config.json new file mode 100644 index 0000000..6000c33 --- /dev/null +++ b/main/boards/lichuang-c3-dev/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "lichuang-c3-dev", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_USE_ESP_WAKE_WORD=y", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/lichuang-c3-dev/lichuang_c3_dev_board.cc b/main/boards/lichuang-c3-dev/lichuang_c3_dev_board.cc new file mode 100644 index 0000000..988246d --- /dev/null +++ b/main/boards/lichuang-c3-dev/lichuang_c3_dev_board.cc @@ -0,0 +1,129 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" + +#include +#include +#include +#include +#include + +#define TAG "LichuangC3DevBoard" + +class LichuangC3DevBoard : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SPI_SCK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 2; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + LichuangC3DevBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + codec_i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(LichuangC3DevBoard); diff --git a/main/boards/lichuang-dev/config.h b/main/boards/lichuang-dev/config.h new file mode 100644 index 0000000..c5d2bf2 --- /dev/null +++ b/main/boards/lichuang-dev/config.h @@ -0,0 +1,62 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_13 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_45 + +#define AUDIO_CODEC_USE_PCA9557 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_1 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_2 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR 0x82 + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_42 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +/* Camera pins */ +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_XCLK GPIO_NUM_5 +#define CAMERA_PIN_SIOD GPIO_NUM_1 +#define CAMERA_PIN_SIOC GPIO_NUM_2 + +#define CAMERA_PIN_D7 GPIO_NUM_9 +#define CAMERA_PIN_D6 GPIO_NUM_4 +#define CAMERA_PIN_D5 GPIO_NUM_6 +#define CAMERA_PIN_D4 GPIO_NUM_15 +#define CAMERA_PIN_D3 GPIO_NUM_17 +#define CAMERA_PIN_D2 GPIO_NUM_8 +#define CAMERA_PIN_D1 GPIO_NUM_18 +#define CAMERA_PIN_D0 GPIO_NUM_16 +#define CAMERA_PIN_VSYNC GPIO_NUM_3 +#define CAMERA_PIN_HREF GPIO_NUM_46 +#define CAMERA_PIN_PCLK GPIO_NUM_7 + +#define XCLK_FREQ_HZ 20000000 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lichuang-dev/config.json b/main/boards/lichuang-dev/config.json new file mode 100644 index 0000000..b35065b --- /dev/null +++ b/main/boards/lichuang-dev/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "lichuang-dev", + "sdkconfig_append": [ + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_CAMERA_GC0308=y", + "CONFIG_CAMERA_GC0308_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_GC0308_DVP_YUV422_640X480_16FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/lichuang-dev/emote.json b/main/boards/lichuang-dev/emote.json new file mode 100644 index 0000000..abc11c8 --- /dev/null +++ b/main/boards/lichuang-dev/emote.json @@ -0,0 +1,22 @@ +[ + {"emote": "happy", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "laughing", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "funny", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "loving", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "embarrassed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confident", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "delicious", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "sad", "src": "Sad.eaf", "loop": true, "fps": 20}, + {"emote": "crying", "src": "cry.eaf", "loop": true, "fps": 20}, + {"emote": "sleepy", "src": "sleep.eaf", "loop": true, "fps": 20}, + {"emote": "silly", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "angry", "src": "angry.eaf", "loop": true, "fps": 20}, + {"emote": "surprised", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "shocked", "src": "shocked.eaf", "loop": true, "fps": 20}, + {"emote": "thinking", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "winking", "src": "neutral.eaf", "loop": true, "fps": 20}, + {"emote": "relaxed", "src": "Happy.eaf", "loop": true, "fps": 20}, + {"emote": "confused", "src": "confused.eaf", "loop": true, "fps": 20}, + {"emote": "neutral", "src": "winking.eaf", "loop": false, "fps": 20}, + {"emote": "idle", "src": "neutral.eaf", "loop": false, "fps": 20} +] diff --git a/main/boards/lichuang-dev/layout.json b/main/boards/lichuang-dev/layout.json new file mode 100644 index 0000000..8a1dfbc --- /dev/null +++ b/main/boards/lichuang-dev/layout.json @@ -0,0 +1,37 @@ +[ + { + "name": "eye_anim", + "align": "GFX_ALIGN_LEFT_MID", + "x": 10, + "y": 30 + }, + { + "name": "status_icon", + "align": "GFX_ALIGN_TOP_MID", + "x": -120, + "y": 18 + }, + { + "name": "toast_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 20, + "width": 200, + "height": 40 + }, + { + "name": "clock_label", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 20, + "width": 200, + "height": 50 + }, + { + "name": "listen_anim", + "align": "GFX_ALIGN_TOP_MID", + "x": 0, + "y": 5 + } +] + \ No newline at end of file diff --git a/main/boards/lichuang-dev/lichuang_dev_board.cc b/main/boards/lichuang-dev/lichuang_dev_board.cc new file mode 100644 index 0000000..fb431a2 --- /dev/null +++ b/main/boards/lichuang-dev/lichuang_dev_board.cc @@ -0,0 +1,281 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "display/emote_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "esp32_camera.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#define TAG "LichuangDevBoard" + +class Pca9557 : public I2cDevice { +public: + Pca9557(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(0x01, 0x03); + WriteReg(0x03, 0xf8); + } + + void SetOutputState(uint8_t bit, uint8_t level) { + uint8_t data = ReadReg(0x01); + data = (data & ~(1 << bit)) | (level << bit); + WriteReg(0x01, data); + } +}; + +class CustomAudioCodec : public BoxAudioCodec { +private: + Pca9557* pca9557_; + +public: + CustomAudioCodec(i2c_master_bus_handle_t i2c_bus, Pca9557* pca9557) + : BoxAudioCodec(i2c_bus, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + GPIO_NUM_NC, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE), + pca9557_(pca9557) { + } + + virtual void EnableOutput(bool enable) override { + BoxAudioCodec::EnableOutput(enable); + if (enable) { + pca9557_->SetOutputState(1, 1); + } else { + pca9557_->SetOutputState(1, 0); + } + } +}; + +class LichuangDevBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + i2c_master_dev_handle_t pca9557_handle_; + Button boot_button_; + Display* display_; + Pca9557* pca9557_; + Esp32Camera* camera_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + // Initialize PCA9557 + pca9557_ = new Pca9557(i2c_bus_, 0x19); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_40; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_41; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_NC; + io_config.dc_gpio_num = GPIO_NUM_39; + io_config.spi_mode = 2; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + pca9557_->SetOutputState(0, 0); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + +#if CONFIG_USE_EMOTE_MESSAGE_STYLE + display_ = new emote::EmoteDisplay(panel, panel_io, DISPLAY_WIDTH, DISPLAY_HEIGHT); +#else + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); +#endif + } + + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_HEIGHT, + .y_max = DISPLAY_WIDTH, + .rst_gpio_num = GPIO_NUM_NC, // Shared with LCD reset + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 1, + .mirror_x = 1, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_FT5x06_CONFIG(); + tp_io_config.scl_speed_hz = 400000; + + esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle); + esp_lcd_touch_new_i2c_ft5x06(tp_io_handle, &tp_cfg, &tp); + assert(tp); + + /* Add touch input (for selected screen) */ + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + + if(touch_cfg.disp) { + lvgl_port_add_touch(&touch_cfg); + } else { + ESP_LOGE(TAG, "Touch display is not initialized"); + } + } + + void InitializeCamera() { + // Open camera power + pca9557_->SetOutputState(2, 0); + + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + LichuangDevBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeTouch(); + InitializeButtons(); + InitializeCamera(); + + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static CustomAudioCodec audio_codec( + i2c_bus_, + pca9557_); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(LichuangDevBoard); diff --git a/main/boards/lilygo-t-cameraplus-s3/README.md b/main/boards/lilygo-t-cameraplus-s3/README.md new file mode 100644 index 0000000..e3c3935 --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/README.md @@ -0,0 +1,47 @@ +## LILYGO T-CameraPlus-S3 + +T-CameraPlus-S3 is an intelligent camera module developed based on the ESP32S3 chip, equipped with a 240x240 TFT display, digital microphone, speaker, independent button, power control chip, SD card module, etc. It comes with a basic UI written based on LVGL, which can achieve functions such as file management, music playback, recording, and camera projection (if the factory does not write the program, you need to manually burn the UI program named "Lvgl_UI"). + +Official github: [T-CameraPlus-S3](https://github.com/Xinyuan-LilyGO/T-CameraPlus-S3) + +## Configuration + +**Set the compilation target to ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**Open menuconfig** + +```bash +idf.py menuconfig +``` + +**Select the board** + +``` +Xiaozhi Assistant -> Board Type -> LILYGO T-CameraPlus-S3_V1_0_V1_1 +Or +Xiaozhi Assistant -> Board Type -> LILYGO T-CameraPlus-S3_V1_2 +``` + +**Modify the psram configuration** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> Quad Mode PSRAM +``` + + +**Select and set camera sensor** + +``` +Component config -> Espressif Camera Sensors Configurations -> Camera Sensor Configuration -> Select and Set Camera Sensor -> OV2640 -> Select default output format for DVP interface -> YUV422 240x240 25fps, DVP 8-bit, 20M input +``` + + +**Build** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/lilygo-t-cameraplus-s3/config.h b/main/boards/lilygo-t-cameraplus-s3/config.h new file mode 100644 index 0000000..0d69e69 --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/config.h @@ -0,0 +1,57 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include "pin_config.h" + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#ifdef CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1 +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_MIC_I2S_GPIO_BCLK MSM261_BCLK +#define AUDIO_MIC_I2S_GPIO_WS MSM261_WS +#define AUDIO_MIC_I2S_GPIO_DATA MSM261_DATA +#elif defined CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 +#define AUDIO_INPUT_REFERENCE false +#define AUDIO_MIC_I2S_GPIO_BCLK GPIO_NUM_NC +#define AUDIO_MIC_I2S_GPIO_WS MP34DT05TR_LRCLK +#define AUDIO_MIC_I2S_GPIO_DATA MP34DT05TR_DATA + +#define AUDIO_MIC_SPKR_EN MP34DT05TR_MAX98357_EN +#endif + +#define AUDIO_SPKR_I2S_GPIO_BCLK MAX98357A_BCLK +#define AUDIO_SPKR_I2S_GPIO_LRCLK MAX98357A_LRCLK +#define AUDIO_SPKR_I2S_GPIO_DATA MAX98357A_DATA + +#define TOUCH_I2C_SDA_PIN TP_SDA +#define TOUCH_I2C_SCL_PIN TP_SCL + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define KEY1_BUTTON_GPIO KEY1 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH LCD_WIDTH +#define DISPLAY_HEIGHT LCD_HEIGHT +#define DISPLAY_MOSI LCD_MOSI +#define DISPLAY_SCLK LCD_SCLK +#define DISPLAY_DC LCD_DC +#define DISPLAY_RST LCD_RST +#define DISPLAY_CS LCD_CS +#define DISPLAY_BL LCD_BL +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN DISPLAY_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define AP1511B_GPIO AP1511B_FBC + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lilygo-t-cameraplus-s3/config.json b/main/boards/lilygo-t-cameraplus-s3/config.json new file mode 100644 index 0000000..a638644 --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/config.json @@ -0,0 +1,23 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "lilygo-t-cameraplus-s3", + "sdkconfig_append": [ + "CONFIG_SPIRAM_MODE_QUAD=y", + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_240X240_25FPS=y" + ] + }, + { + "name": "lilygo-t-cameraplus-s3_v1_2", + "sdkconfig_append": [ + "CONFIG_SPIRAM_MODE_QUAD=y", + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_240X240_25FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/lilygo-t-cameraplus-s3/ir_filter_controller.h b/main/boards/lilygo-t-cameraplus-s3/ir_filter_controller.h new file mode 100644 index 0000000..3ae619a --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/ir_filter_controller.h @@ -0,0 +1,44 @@ +#ifndef __IR_FILTER_CONTROLLER_H__ +#define __IR_FILTER_CONTROLLER_H__ + +#include "mcp_server.h" + + +class IrFilterController { +private: + bool enable_ = false; + gpio_num_t gpio_num_; + +public: + IrFilterController(gpio_num_t gpio_num) : gpio_num_(gpio_num) { + gpio_config_t config = { + .pin_bit_mask = (1ULL << gpio_num_), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + ESP_ERROR_CHECK(gpio_config(&config)); + gpio_set_level(gpio_num_, 0); + + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.camera.get_ir_filter_state", "Get the state of the camera's infrared filter", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return enable_ ? "{\"enable\": true}" : "{\"enable\": false}"; + }); + + mcp_server.AddTool("self.camera.enable_ir_filter", "Enable the camera's infrared filter", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + enable_ = true; + gpio_set_level(gpio_num_, 1); + return true; + }); + + mcp_server.AddTool("self.camera.disable_ir_filter", "Disable the camera's infrared filter", PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + enable_ = false; + gpio_set_level(gpio_num_, 0); + return true; + }); + } +}; + + +#endif // __IR_FILTER_CONTROLLER_H__ diff --git a/main/boards/lilygo-t-cameraplus-s3/lilygo-t-cameraplus-s3.cc b/main/boards/lilygo-t-cameraplus-s3/lilygo-t-cameraplus-s3.cc new file mode 100644 index 0000000..8e1424f --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/lilygo-t-cameraplus-s3.cc @@ -0,0 +1,349 @@ +#include "wifi_board.h" +#include "tcamerapluss3_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "i2c_device.h" +#include "sy6970.h" +#include "pin_config.h" +#include "esp32_camera.h" +#include "ir_filter_controller.h" + +#include +#include +#include +#include + +#define TAG "LilygoTCameraPlusS3Board" + +class Cst816x : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + Cst816x(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA7); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Cst816x() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t &GetTouchPoint() { + return tp_; + } + +private: + uint8_t *read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class Pmic : public Sy6970 { +public: + + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Sy6970(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0x14); + ESP_LOGI(TAG, "Get sy6970 chip ID: 0x%02X", (chip_id & 0B00111000)); + + WriteReg(0x00, 0B00001000); // Disable ILIM pin + WriteReg(0x02, 0B11011101); // Enable ADC measurement function + WriteReg(0x07, 0B10001101); // Disable watchdog timer feeding function + } +}; + +class LilygoTCameraPlusS3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Cst816x *cst816d_; + Pmic* pmic_; + LcdDisplay *display_; + Button boot_button_; + Button key1_button_; + PowerSaveTimer* power_save_timer_; + Esp32Camera* camera_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, -1); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitI2c(){ + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_config = { + .i2c_port = I2C_NUM_0, + .sda_io_num = TOUCH_I2C_SDA_PIN, + .scl_io_num = TOUCH_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + } + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_config, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + static void TouchpadDaemon(void *param) { + vTaskDelay(pdMS_TO_TICKS(2000)); + auto &board = (LilygoTCameraPlusS3Board&)Board::GetInstance(); + auto touchpad = board.GetTouchpad(); + bool was_touched = false; + while (1) { + touchpad->UpdateTouchPoint(); + if (touchpad->GetTouchPoint().num > 0){ + // On press + if (!was_touched) { + was_touched = true; + Application::GetInstance().ToggleChatState(); + } + } + // On release + else if (was_touched) { + was_touched = false; + } + vTaskDelay(pdMS_TO_TICKS(50)); + } + vTaskDelete(NULL); + } + + void InitCst816d() { + ESP_LOGI(TAG, "Init CST816x"); + cst816d_ = new Cst816x(i2c_bus_, CST816_ADDRESS); + xTaskCreate(TouchpadDaemon, "tp", 2048, NULL, 5, NULL); + } + + void InitSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitSy6970() { + ESP_LOGI(TAG, "Init Sy6970"); + pmic_ = new Pmic(i2c_bus_, SY6970_ADDRESS); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS; + io_config.dc_gpio_num = LCD_DC; + io_config.spi_mode = 0; + io_config.pclk_hz = 60 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + power_save_timer_->WakeUp(); + app.ToggleChatState(); + }); + key1_button_.OnClick([this]() { + if (camera_) { + camera_->Capture(); + } + }); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = Y2_GPIO_NUM, + [1] = Y3_GPIO_NUM, + [2] = Y4_GPIO_NUM, + [3] = Y5_GPIO_NUM, + [4] = Y6_GPIO_NUM, + [5] = Y7_GPIO_NUM, + [6] = Y8_GPIO_NUM, + [7] = Y9_GPIO_NUM, + }, + .vsync_io = VSYNC_GPIO_NUM, + .de_io = HREF_GPIO_NUM, + .pclk_io = PCLK_GPIO_NUM, + .xclk_io = XCLK_GPIO_NUM, + }; + + esp_video_init_sccb_config_t sccb_config = { +#ifdef CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1 + .init_sccb = false, + .i2c_handle = i2c_bus_, +#elif defined CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 + .init_sccb = true, + .i2c_config = { + .port = 1, + .scl_pin = SIOC_GPIO_NUM, + .sda_pin = SIOD_GPIO_NUM, + }, +#endif + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = RESET_GPIO_NUM, + .pwdn_pin = PWDN_GPIO_NUM, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + camera_->SetVFlip(1); + camera_->SetHMirror(1); + } + + void InitializeTools() { + static IrFilterController irFilter(AP1511B_GPIO); + } + +public: + LilygoTCameraPlusS3Board() : boot_button_(BOOT_BUTTON_GPIO), key1_button_(KEY1_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitI2c(); + InitSy6970(); + InitCst816d(); + I2cDetect(); + InitSpi(); + InitializeSt7789Display(); + InitializeButtons(); + InitializeCamera(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Tcamerapluss3AudioCodec audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_MIC_I2S_GPIO_BCLK, + AUDIO_MIC_I2S_GPIO_WS, + AUDIO_MIC_I2S_GPIO_DATA, + AUDIO_SPKR_I2S_GPIO_BCLK, + AUDIO_SPKR_I2S_GPIO_LRCLK, + AUDIO_SPKR_I2S_GPIO_DATA, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override{ + return display_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + bool is_power_good = pmic_->IsPowerGood(); + discharging = !charging && is_power_good; + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst816x *GetTouchpad() { + return cst816d_; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(LilygoTCameraPlusS3Board); diff --git a/main/boards/lilygo-t-cameraplus-s3/pin_config.h b/main/boards/lilygo-t-cameraplus-s3/pin_config.h new file mode 100644 index 0000000..82ab983 --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/pin_config.h @@ -0,0 +1,154 @@ +/* + * @Description: None + * @Author: LILYGO_L + * @Date: 2024-11-11 11:36:49 + * @LastEditTime: 2025-06-03 17:37:08 + * @License: GPL 3.0 + */ +#pragma once + +#ifdef CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1 +#define T_CameraPlus_S3_V1_0_V1_1 +#elif defined CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 +#define T_CameraPlus_S3_V1_2 +#endif + +#ifdef T_CameraPlus_S3_V1_0_V1_1 + +// SPI +#define SPI_SCLK GPIO_NUM_36 +#define SPI_MOSI GPIO_NUM_35 +#define SPI_MISO GPIO_NUM_37 + +// IIC +#define IIC_SDA GPIO_NUM_1 +#define IIC_SCL GPIO_NUM_2 + +// MSM261 +#define MSM261_BCLK GPIO_NUM_18 +#define MSM261_WS GPIO_NUM_39 +#define MSM261_DATA GPIO_NUM_40 + +// MAX98357A +#define MAX98357A_DATA GPIO_NUM_38 + +// FP-133H01D +#define LCD_CS GPIO_NUM_34 +#define LCD_RST GPIO_NUM_33 + +// OV2640 +#define OV2640_PWDN GPIO_NUM_NC +#define OV2640_RESET GPIO_NUM_3 +#define OV2640_VSYNC GPIO_NUM_4 + +// CST816 +#define TP_RST GPIO_NUM_48 + +// SY6970 +#define SY6970_INT GPIO_NUM_47 + +#endif + +#ifdef T_CameraPlus_S3_V1_2 + +// SPI +#define SPI_SCLK GPIO_NUM_35 +#define SPI_MOSI GPIO_NUM_34 +#define SPI_MISO GPIO_NUM_48 + +// IIC +#define IIC_SDA GPIO_NUM_33 +#define IIC_SCL GPIO_NUM_37 + +// MP34DT05TR +#define MP34DT05TR_LRCLK GPIO_NUM_40 +#define MP34DT05TR_DATA GPIO_NUM_38 + +#define MP34DT05TR_MAX98357_EN GPIO_NUM_18 + +// MAX98357A +#define MAX98357A_DATA GPIO_NUM_39 + +// FP-133H01D +#define LCD_CS GPIO_NUM_36 +#define LCD_RST GPIO_NUM_NC + +// OV2640 +#define OV2640_PWDN GPIO_NUM_4 +#define OV2640_RESET GPIO_NUM_NC +#define OV2640_VSYNC GPIO_NUM_3 + +// CST816 +#define TP_RST GPIO_NUM_NC + +#endif + +// SD +#define SD_CS GPIO_NUM_21 +#define SD_SCLK SPI_SCLK +#define SD_MOSI SPI_MOSI +#define SD_MISO SPI_MISO + +// MAX98357A +#define MAX98357A_BCLK GPIO_NUM_41 +#define MAX98357A_LRCLK GPIO_NUM_42 + +// FP-133H01D +#define LCD_WIDTH 240 +#define LCD_HEIGHT 240 +#define LCD_BL GPIO_NUM_46 +#define LCD_MOSI SPI_MOSI +#define LCD_SCLK SPI_SCLK +#define LCD_DC GPIO_NUM_45 + +// SY6970 +#define SY6970_SDA IIC_SDA +#define SY6970_SCL IIC_SCL +#define SY6970_ADDRESS 0x6A + +// OV2640 +#define OV2640_XCLK GPIO_NUM_7 +#define OV2640_SDA GPIO_NUM_1 +#define OV2640_SCL GPIO_NUM_2 +#define OV2640_D9 GPIO_NUM_6 +#define OV2640_D8 GPIO_NUM_8 +#define OV2640_D7 GPIO_NUM_9 +#define OV2640_D6 GPIO_NUM_11 +#define OV2640_D5 GPIO_NUM_13 +#define OV2640_D4 GPIO_NUM_15 +#define OV2640_D3 GPIO_NUM_14 +#define OV2640_D2 GPIO_NUM_12 +#define OV2640_HREF GPIO_NUM_5 +#define OV2640_PCLK GPIO_NUM_10 + +#define PWDN_GPIO_NUM OV2640_PWDN +#define RESET_GPIO_NUM OV2640_RESET +#define XCLK_GPIO_NUM OV2640_XCLK +#define SIOD_GPIO_NUM OV2640_SDA +#define SIOC_GPIO_NUM OV2640_SCL + +#define Y9_GPIO_NUM OV2640_D9 +#define Y8_GPIO_NUM OV2640_D8 +#define Y7_GPIO_NUM OV2640_D7 +#define Y6_GPIO_NUM OV2640_D6 +#define Y5_GPIO_NUM OV2640_D5 +#define Y4_GPIO_NUM OV2640_D4 +#define Y3_GPIO_NUM OV2640_D3 +#define Y2_GPIO_NUM OV2640_D2 +#define VSYNC_GPIO_NUM OV2640_VSYNC +#define HREF_GPIO_NUM OV2640_HREF +#define PCLK_GPIO_NUM OV2640_PCLK + +#define XCLK_FREQ_HZ 20000000 + +// CST816 +#define CST816_ADDRESS 0x15 +#define TP_SDA IIC_SDA +#define TP_SCL IIC_SCL +#define TP_INT GPIO_NUM_47 + +// AP1511B +#define AP1511B_FBC GPIO_NUM_16 + +// KEY +#define KEY1 GPIO_NUM_17 diff --git a/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.cc b/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.cc new file mode 100644 index 0000000..365d9ca --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.cc @@ -0,0 +1,169 @@ +#include "tcamerapluss3_audio_codec.h" + +#include +#include +#include +#include + +#include "config.h" + +static const char TAG[] = "Tcamerapluss3AudioCodec"; + +Tcamerapluss3AudioCodec::Tcamerapluss3AudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateVoiceHardware(mic_bclk, mic_ws, mic_data, spkr_bclk, spkr_lrclk, spkr_data); + + ESP_LOGI(TAG, "Tcamerapluss3AudioCodec initialized"); + +#ifdef CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 + gpio_config_t config_mic_spkr_en; + config_mic_spkr_en.pin_bit_mask = BIT64(AUDIO_MIC_SPKR_EN); + config_mic_spkr_en.mode = GPIO_MODE_OUTPUT; + config_mic_spkr_en.pull_up_en = GPIO_PULLUP_ENABLE; + config_mic_spkr_en.pull_down_en = GPIO_PULLDOWN_DISABLE; + config_mic_spkr_en.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER +config_mic_spkr_en.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config_mic_spkr_en); + gpio_set_level(AUDIO_MIC_SPKR_EN, 0); +#endif +} + +Tcamerapluss3AudioCodec::~Tcamerapluss3AudioCodec() { + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Tcamerapluss3AudioCodec::CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data) { + + i2s_chan_config_t mic_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(I2S_NUM_0, I2S_ROLE_MASTER); + mic_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + i2s_chan_config_t spkr_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(I2S_NUM_1, I2S_ROLE_MASTER); + spkr_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + + ESP_ERROR_CHECK(i2s_new_channel(&mic_chan_config, NULL, &rx_handle_)); + ESP_ERROR_CHECK(i2s_new_channel(&spkr_chan_config, &tx_handle_, NULL)); + + #ifdef CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_0_V1_1 + i2s_std_config_t mic_config = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = I2S_STD_PHILIPS_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO), + .gpio_cfg = { + .mclk = I2S_GPIO_UNUSED, + .bclk = mic_bclk, + .ws = mic_ws, + .dout = I2S_GPIO_UNUSED, + .din = mic_data, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = true // 默认右通道 + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &mic_config)); +#elif defined CONFIG_BOARD_TYPE_LILYGO_T_CAMERAPLUS_S3_V1_2 + i2s_pdm_rx_config_t mic_config = { + .clk_cfg = I2S_PDM_RX_CLK_DEFAULT_CONFIG(static_cast(input_sample_rate_)), + /* The data bit-width of PDM mode is fixed to 16 */ + .slot_cfg = I2S_PDM_RX_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO), + .gpio_cfg = { + .clk = mic_ws, + .din = mic_data, + .invert_flags = { + .clk_inv = false, + }, + }, + }; + + ESP_ERROR_CHECK(i2s_channel_init_pdm_rx_mode(rx_handle_, &mic_config)); +#endif + + i2s_std_config_t spkr_config = { + .clk_cfg ={ + .sample_rate_hz = static_cast(11025), + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + }, + .slot_cfg = I2S_STD_PHILIPS_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_STEREO), + .gpio_cfg ={ + .mclk = I2S_GPIO_UNUSED, + .bclk = spkr_bclk, + .ws = spkr_lrclk, + .dout = spkr_data, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &spkr_config)); + ESP_LOGI(TAG, "Voice hardware created"); +} + +void Tcamerapluss3AudioCodec::SetOutputVolume(int volume) { + volume_ = volume; + AudioCodec::SetOutputVolume(volume); +} + +void Tcamerapluss3AudioCodec::EnableInput(bool enable) { + AudioCodec::EnableInput(enable); +} + +void Tcamerapluss3AudioCodec::EnableOutput(bool enable) { + AudioCodec::EnableOutput(enable); +} + +int Tcamerapluss3AudioCodec::Read(int16_t *dest, int samples) { + if (input_enabled_) { + size_t bytes_read; + i2s_channel_read(rx_handle_, dest, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + + // 麦克风接收音量放大20倍(限制在 int16_t 范围内防止溢出) + int16_t *ptr = dest; + for (int i = 0; i < samples; i++) { + int32_t amplified = *ptr * 20; + *ptr++ = (amplified > 32767) ? 32767 : (amplified < -32768) ? -32768 : amplified; + } + } + return samples; +} + +int Tcamerapluss3AudioCodec::Write(const int16_t *data, int samples){ + if (output_enabled_){ + size_t bytes_read; + auto output_data = (int16_t *)malloc(samples * sizeof(int16_t)); + for (size_t i = 0; i < samples; i++){ + output_data[i] = (float)data[i] * (float)(volume_ / 100.0); + } + i2s_channel_write(tx_handle_, output_data, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + free(output_data); + } + return samples; +} diff --git a/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.h b/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.h new file mode 100644 index 0000000..cdb9aaa --- /dev/null +++ b/main/boards/lilygo-t-cameraplus-s3/tcamerapluss3_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _TCIRCLES3_AUDIO_CODEC_H +#define _TCIRCLES3_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class Tcamerapluss3AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t *data_if_ = nullptr; + const audio_codec_ctrl_if_t *out_ctrl_if_ = nullptr; + const audio_codec_if_t *out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t *in_ctrl_if_ = nullptr; + const audio_codec_if_t *in_codec_if_ = nullptr; + const audio_codec_gpio_if_t *gpio_if_ = nullptr; + + uint32_t volume_ = 70; + + void CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data,gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data); + + virtual int Read(int16_t *dest, int samples) override; + virtual int Write(const int16_t *data, int samples) override; + +public: + Tcamerapluss3AudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference); + virtual ~Tcamerapluss3AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/lilygo-t-circle-s3/README.md b/main/boards/lilygo-t-circle-s3/README.md new file mode 100644 index 0000000..6b7b678 --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/README.md @@ -0,0 +1,28 @@ +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> LILYGO T-Circle-S3 +``` + + +**编译:** + +```bash +idf.py build +``` + +LILYGO T-Circle-S3 \ No newline at end of file diff --git a/main/boards/lilygo-t-circle-s3/config.h b/main/boards/lilygo-t-circle-s3/config.h new file mode 100644 index 0000000..03e4fc5 --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/config.h @@ -0,0 +1,46 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include "pin_config.h" + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_MIC_I2S_GPIO_BCLK static_cast(MSM261_BCLK) +#define AUDIO_MIC_I2S_GPIO_WS static_cast(MSM261_WS) +#define AUDIO_MIC_I2S_GPIO_DATA static_cast(MSM261_DATA) + +#define AUDIO_SPKR_I2S_GPIO_BCLK static_cast(MAX98357A_BCLK) +#define AUDIO_SPKR_I2S_GPIO_LRCLK static_cast(MAX98357A_LRCLK) +#define AUDIO_SPKR_I2S_GPIO_DATA static_cast(MAX98357A_DATA) +#define AUDIO_SPKR_ENABLE static_cast(MAX98357A_SD_MODE) + +#define TOUCH_I2C_SDA_PIN static_cast(TP_SDA) +#define TOUCH_I2C_SCL_PIN static_cast(TP_SCL) + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH LCD_WIDTH +#define DISPLAY_HEIGHT LCD_HEIGHT +#define DISPLAY_MOSI LCD_MOSI +#define DISPLAY_SCLK LCD_SCLK +#define DISPLAY_DC LCD_DC +#define DISPLAY_RST LCD_RST +#define DISPLAY_CS LCD_CS +#define DISPLAY_BL static_cast(LCD_BL) +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN DISPLAY_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lilygo-t-circle-s3/config.json b/main/boards/lilygo-t-circle-s3/config.json new file mode 100644 index 0000000..378dded --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "lilygo-t-circle-s3", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.c b/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.c new file mode 100644 index 0000000..25a7867 --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.c @@ -0,0 +1,353 @@ +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "esp_lcd_panel_interface.h" +#include "esp_lcd_panel_io.h" +#include "esp_lcd_panel_vendor.h" +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_panel_commands.h" +#include "driver/gpio.h" +#include "esp_log.h" +#include "esp_check.h" + +#include "esp_lcd_gc9d01n.h" + +static const char *TAG = "gc9d01n"; + +static esp_err_t panel_gc9d01n_del(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9d01n_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9d01n_init(esp_lcd_panel_t *panel); +static esp_err_t panel_gc9d01n_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data); +static esp_err_t panel_gc9d01n_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); +static esp_err_t panel_gc9d01n_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_gc9d01n_swap_xy(esp_lcd_panel_t *panel, bool swap_axes); +static esp_err_t panel_gc9d01n_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap); +static esp_err_t panel_gc9d01n_disp_on_off(esp_lcd_panel_t *panel, bool off); + +typedef struct{ + esp_lcd_panel_t base; + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + bool reset_level; + int x_gap; + int y_gap; + uint8_t fb_bits_per_pixel; + uint8_t madctl_val; // save current value of LCD_CMD_MADCTL register + uint8_t colmod_val; // save current value of LCD_CMD_COLMOD register + const gc9d01n_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; +} gc9d01n_panel_t; + +esp_err_t esp_lcd_new_panel_gc9d01n(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, esp_lcd_panel_handle_t *ret_panel){ + esp_err_t ret = ESP_OK; + gc9d01n_panel_t *gc9d01n = NULL; + gpio_config_t io_conf = {0}; + + ESP_GOTO_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument"); + gc9d01n = (gc9d01n_panel_t *)calloc(1, sizeof(gc9d01n_panel_t)); + ESP_GOTO_ON_FALSE(gc9d01n, ESP_ERR_NO_MEM, err, TAG, "no mem for gc9d01n panel"); + + if (panel_dev_config->reset_gpio_num >= 0){ + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + switch (panel_dev_config->color_space){ + case ESP_LCD_COLOR_SPACE_RGB: + gc9d01n->madctl_val = 0; + break; + case ESP_LCD_COLOR_SPACE_BGR: + gc9d01n->madctl_val |= LCD_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color space"); + break; + } +#else + switch (panel_dev_config->rgb_endian){ + case LCD_RGB_ENDIAN_RGB: + gc9d01n->madctl_val = 0; + break; + case LCD_RGB_ENDIAN_BGR: + gc9d01n->madctl_val |= LCD_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported rgb endian"); + break; + } +#endif + + switch (panel_dev_config->bits_per_pixel){ + case 16: // RGB565 + gc9d01n->colmod_val = 0x55; + gc9d01n->fb_bits_per_pixel = 16; + break; + case 18: // RGB666 + gc9d01n->colmod_val = 0x66; + // each color component (R/G/B) should occupy the 6 high bits of a byte, which means 3 full bytes are required for a pixel + gc9d01n->fb_bits_per_pixel = 24; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + gc9d01n->io = io; + gc9d01n->reset_gpio_num = panel_dev_config->reset_gpio_num; + gc9d01n->reset_level = panel_dev_config->flags.reset_active_high; + if (panel_dev_config->vendor_config){ + gc9d01n->init_cmds = ((gc9d01n_vendor_config_t *)panel_dev_config->vendor_config)->init_cmds; + gc9d01n->init_cmds_size = ((gc9d01n_vendor_config_t *)panel_dev_config->vendor_config)->init_cmds_size; + } + gc9d01n->base.del = panel_gc9d01n_del; + gc9d01n->base.reset = panel_gc9d01n_reset; + gc9d01n->base.init = panel_gc9d01n_init; + gc9d01n->base.draw_bitmap = panel_gc9d01n_draw_bitmap; + gc9d01n->base.invert_color = panel_gc9d01n_invert_color; + gc9d01n->base.set_gap = panel_gc9d01n_set_gap; + gc9d01n->base.mirror = panel_gc9d01n_mirror; + gc9d01n->base.swap_xy = panel_gc9d01n_swap_xy; +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + gc9d01n->base.disp_off = panel_gc9d01n_disp_on_off; +#else + gc9d01n->base.disp_on_off = panel_gc9d01n_disp_on_off; +#endif + *ret_panel = &(gc9d01n->base); + ESP_LOGD(TAG, "new gc9d01n panel @%p", gc9d01n); + + // ESP_LOGI(TAG, "LCD panel create success, version: %d.%d.%d", ESP_LCD_GC9D01N_VER_MAJOR, ESP_LCD_GC9D01N_VER_MINOR, + // ESP_LCD_GC9D01N_VER_PATCH); + + return ESP_OK; + +err: + if (gc9d01n){ + if (panel_dev_config->reset_gpio_num >= 0){ + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(gc9d01n); + } + return ret; +} + +static esp_err_t panel_gc9d01n_del(esp_lcd_panel_t *panel){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + + if (gc9d01n->reset_gpio_num >= 0){ + gpio_reset_pin(gc9d01n->reset_gpio_num); + } + ESP_LOGD(TAG, "del gc9d01n panel @%p", gc9d01n); + free(gc9d01n); + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_reset(esp_lcd_panel_t *panel){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + + // perform hardware reset + if (gc9d01n->reset_gpio_num >= 0){ + gpio_set_level(gc9d01n->reset_gpio_num, gc9d01n->reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(gc9d01n->reset_gpio_num, !gc9d01n->reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + } + else{ // perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(20)); // spec, wait at least 5ms before sending new command + } + + return ESP_OK; +} + +static const gc9d01n_lcd_init_cmd_t vendor_specific_init_default[] = { + // {cmd, { data }, data_size, delay_ms} + // Enable Inter Register + {0xFE, (uint8_t[]){0x00}, 0, 0}, + {0xEF, (uint8_t[]){0x00}, 0, 0}, + {0x80, (uint8_t[]){0xFF}, 1, 0}, + {0x81, (uint8_t[]){0xFF}, 1, 0}, + {0x82, (uint8_t[]){0xFF}, 1, 0}, + {0x84, (uint8_t[]){0xFF}, 1, 0}, + {0x85, (uint8_t[]){0xFF}, 1, 0}, + {0x86, (uint8_t[]){0xFF}, 1, 0}, + {0x87, (uint8_t[]){0xFF}, 1, 0}, + {0x88, (uint8_t[]){0xFF}, 1, 0}, + {0x89, (uint8_t[]){0xFF}, 1, 0}, + {0x8A, (uint8_t[]){0xFF}, 1, 0}, + {0x8B, (uint8_t[]){0xFF}, 1, 0}, + {0x8C, (uint8_t[]){0xFF}, 1, 0}, + {0x8D, (uint8_t[]){0xFF}, 1, 0}, + {0x8E, (uint8_t[]){0xFF}, 1, 0}, + {0x8F, (uint8_t[]){0xFF}, 1, 0}, + {0x3A, (uint8_t[]){0x05}, 1, 0}, + {0xEC, (uint8_t[]){0x01}, 1, 0}, + {0x74, (uint8_t[]){0x02, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00}, 7, 0}, + {0x98, (uint8_t[]){0x3E}, 1, 0}, + {0x99, (uint8_t[]){0x3E}, 1, 0}, + {0xB5, (uint8_t[]){0x0D, 0x0D}, 2, 0}, + {0x60, (uint8_t[]){0x38, 0x0F, 0x79, 0x67}, 4, 0}, + {0x61, (uint8_t[]){0x38, 0x11, 0x79, 0x67}, 4, 0}, + {0x64, (uint8_t[]){0x38, 0x17, 0x71, 0x5F, 0x79, 0x67}, 6, 0}, + {0x65, (uint8_t[]){0x38, 0x13, 0x71, 0x5B, 0x79, 0x67}, 6, 0}, + {0x6A, (uint8_t[]){0x00, 0x00}, 2, 0}, + {0x6C, (uint8_t[]){0x22, 0x02, 0x22, 0x02, 0x22, 0x22, 0x50}, 7, 0}, + {0x6E, (uint8_t[]){0x03, 0x03, 0x01, 0x01, 0x00, 0x00, 0x0F, 0x0F, 0x0D, 0x0D, 0x0B, 0x0B, 0x09, 0x09, 0x00, 0x00, 0x00, 0x00, 0x0A, 0x0A, 0x0C, 0x0C, 0x0E, 0x0E, 0x10, 0x10, 0x00, 0x00, 0x02, 0x02, 0x04, 0x04}, 32, 0}, + {0xBF, (uint8_t[]){0x01}, 1, 0}, + {0xF9, (uint8_t[]){0x40}, 1, 0}, + {0x9B, (uint8_t[]){0x3B, 0x93, 0x33, 0x7F, 0x00}, 5, 0}, + {0x7E, (uint8_t[]){0x30}, 1, 0}, + {0x70, (uint8_t[]){0x0D, 0x02, 0x08, 0x0D, 0x02, 0x08}, 6, 0}, + {0x71, (uint8_t[]){0x0D, 0x02, 0x08}, 3, 0}, + {0x91, (uint8_t[]){0x0E, 0x09}, 2, 0}, + {0xC3, (uint8_t[]){0x19, 0xC4, 0x19, 0xC9, 0x3C}, 5, 0}, + {0xF0, (uint8_t[]){0x53, 0x15, 0x0A, 0x04, 0x00, 0x3E}, 6, 0}, + {0xF1, (uint8_t[]){0x56, 0xA8, 0x7F, 0x33, 0x34, 0x5F}, 6, 0}, + {0xF2, (uint8_t[]){0x53, 0x15, 0x0A, 0x04, 0x00, 0x3A}, 6, 0}, + {0xF3, (uint8_t[]){0x52, 0xA4, 0x7F, 0x33, 0x34, 0xDF}, 6, 0}, + + // {0x20, (uint8_t[]){0x00}, 0, 0}, + {0x36, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 0, 200}, + {0x29, (uint8_t[]){0x00}, 0, 0}, + {0x2C, (uint8_t[]){0x00}, 0, 20}, +}; + +static esp_err_t panel_gc9d01n_init(esp_lcd_panel_t *panel){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + + // LCD goes into sleep mode and display will be turned off after power on reset, exit sleep mode first + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SLPOUT, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(100)); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){gc9d01n->madctl_val,},1),TAG, "send command failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]){gc9d01n->colmod_val,},1),TAG, "send command failed"); + + const gc9d01n_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + if (gc9d01n->init_cmds){ + init_cmds = gc9d01n->init_cmds; + init_cmds_size = gc9d01n->init_cmds_size; + }else{ + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(gc9d01n_lcd_init_cmd_t); + } + + bool is_cmd_overwritten = false; + for (int i = 0; i < init_cmds_size; i++){ + // Check if the command has been used or conflicts with the internal + switch (init_cmds[i].cmd){ + case LCD_CMD_MADCTL: + is_cmd_overwritten = true; + gc9d01n->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + case LCD_CMD_COLMOD: + is_cmd_overwritten = true; + gc9d01n->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + default: + is_cmd_overwritten = false; + break; + } + + if (is_cmd_overwritten){ + ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", init_cmds[i].cmd); + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + } + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + assert((x_start < x_end) && (y_start < y_end) && "start position must be smaller than end position"); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + + x_start += gc9d01n->x_gap; + x_end += gc9d01n->x_gap; + y_start += gc9d01n->y_gap; + y_end += gc9d01n->y_gap; + + // define an area of frame memory where MCU can access + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_CASET, (uint8_t[]){(x_start >> 8) & 0xFF,x_start & 0xFF,((x_end - 1) >> 8) & 0xFF,(x_end - 1) & 0xFF,},4),TAG, "send command failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_RASET, (uint8_t[]){(y_start >> 8) & 0xFF,y_start & 0xFF,((y_end - 1) >> 8) & 0xFF,(y_end - 1) & 0xFF,},4),TAG, "send command failed"); + // transfer frame buffer + size_t len = (x_end - x_start) * (y_end - y_start) * gc9d01n->fb_bits_per_pixel / 8; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_color(io, LCD_CMD_RAMWR, color_data, len), TAG, "send color failed"); + + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_invert_color(esp_lcd_panel_t *panel, bool invert_color_data){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + int command = 0; + if (invert_color_data){ + command = LCD_CMD_INVON; + }else{ + command = LCD_CMD_INVOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + if (mirror_x){ + gc9d01n->madctl_val |= LCD_CMD_MX_BIT; + }else{ + gc9d01n->madctl_val &= ~LCD_CMD_MX_BIT; + } + if (mirror_y){ + gc9d01n->madctl_val |= LCD_CMD_MY_BIT; + }else{ + gc9d01n->madctl_val &= ~LCD_CMD_MY_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){gc9d01n->madctl_val}, 1), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_swap_xy(esp_lcd_panel_t *panel, bool swap_axes){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + if (swap_axes){ + gc9d01n->madctl_val |= LCD_CMD_MV_BIT; + }else{ + gc9d01n->madctl_val &= ~LCD_CMD_MV_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){gc9d01n->madctl_val}, 1), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + gc9d01n->x_gap = x_gap; + gc9d01n->y_gap = y_gap; + return ESP_OK; +} + +static esp_err_t panel_gc9d01n_disp_on_off(esp_lcd_panel_t *panel, bool on_off){ + gc9d01n_panel_t *gc9d01n = __containerof(panel, gc9d01n_panel_t, base); + esp_lcd_panel_io_handle_t io = gc9d01n->io; + int command = 0; + +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + on_off = !on_off; +#endif + + if (on_off){ + command = LCD_CMD_DISPON; + }else{ + command = LCD_CMD_DISPOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + return ESP_OK; +} diff --git a/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.h b/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.h new file mode 100644 index 0000000..ec057cc --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/esp_lcd_gc9d01n.h @@ -0,0 +1,99 @@ +#pragma once + +#include "esp_lcd_panel_vendor.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct { + int cmd; /* +#include +#include +#include +#include +#include "esp_lcd_gc9d01n.h" + +#define TAG "LilygoTCircleS3Board" + +class Cst816x : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + Cst816x(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA7); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Cst816x() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t &GetTouchPoint() { + return tp_; + } + +private: + uint8_t *read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class LilygoTCircleS3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Cst816x *cst816d_; + LcdDisplay *display_; + Button boot_button_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitI2c(){ + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_config = { + .i2c_port = I2C_NUM_0, + .sda_io_num = TOUCH_I2C_SDA_PIN, + .scl_io_num = TOUCH_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + } + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_config, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + static void touchpad_daemon(void *param) { + vTaskDelay(pdMS_TO_TICKS(2000)); + auto &board = (LilygoTCircleS3Board&)Board::GetInstance(); + auto touchpad = board.GetTouchpad(); + bool was_touched = false; + while (1) { + touchpad->UpdateTouchPoint(); + if (touchpad->GetTouchPoint().num > 0){ + // On press + if (!was_touched) { + was_touched = true; + Application::GetInstance().ToggleChatState(); + } + } + // On release + else if (was_touched) { + was_touched = false; + } + vTaskDelay(pdMS_TO_TICKS(50)); + } + vTaskDelete(NULL); + } + + void InitCst816d() { + ESP_LOGI(TAG, "Init CST816x"); + cst816d_ = new Cst816x(i2c_bus_, 0x15); + xTaskCreate(touchpad_daemon, "tp", 2048, NULL, 5, NULL); + } + + void InitSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitGc9d01nDisplay() { + ESP_LOGI(TAG, "Init GC9D01N"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9d01n(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + gpio_config_t config; + config.pin_bit_mask = BIT64(DISPLAY_BL); + config.mode = GPIO_MODE_OUTPUT; + config.pull_up_en = GPIO_PULLUP_DISABLE; + config.pull_down_en = GPIO_PULLDOWN_ENABLE; + config.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER + config.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config); + gpio_set_level(DISPLAY_BL, 0); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + power_save_timer_->WakeUp(); + app.ToggleChatState(); + }); + } + +public: + LilygoTCircleS3Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitI2c(); + InitCst816d(); + I2cDetect(); + InitSpi(); + InitGc9d01nDisplay(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Tcircles3AudioCodec audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_MIC_I2S_GPIO_BCLK, + AUDIO_MIC_I2S_GPIO_WS, + AUDIO_MIC_I2S_GPIO_DATA, + AUDIO_SPKR_I2S_GPIO_BCLK, + AUDIO_SPKR_I2S_GPIO_LRCLK, + AUDIO_SPKR_I2S_GPIO_DATA, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override{ + return display_; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst816x *GetTouchpad() { + return cst816d_; + } +}; + +DECLARE_BOARD(LilygoTCircleS3Board); diff --git a/main/boards/lilygo-t-circle-s3/pin_config.h b/main/boards/lilygo-t-circle-s3/pin_config.h new file mode 100644 index 0000000..db428ca --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/pin_config.h @@ -0,0 +1,47 @@ +/* + * @Description: None + * @Author: LILYGO_L + * @Date: 2023-08-16 14:24:03 + * @LastEditTime: 2025-01-20 10:11:16 + * @License: GPL 3.0 + */ +#pragma once + +// MAX98357A +#define MAX98357A_BCLK 5 +#define MAX98357A_LRCLK 4 +#define MAX98357A_DATA 6 +#define MAX98357A_SD_MODE 45 + +// MSM261 +#define MSM261_BCLK 7 +#define MSM261_WS 9 +#define MSM261_DATA 8 + +// APA102 +#define APA102_DATA 38 +#define APA102_CLOCK 39 + +// H0075Y002-V0 +#define LCD_WIDTH 160 +#define LCD_HEIGHT 160 +#define LCD_MOSI 17 +#define LCD_SCLK 15 +#define LCD_DC 16 +#define LCD_RST -1 +#define LCD_CS 13 +#define LCD_BL 18 + +// IIC +#define IIC_SDA 11 +#define IIC_SCL 14 + +// CST816D +#define TP_SDA 11 +#define TP_SCL 14 +#define TP_RST -1 +#define TP_INT 12 + +//Rotary Encoder +#define KNOB_DATA_A 47 +#define KNOB_DATA_B 48 diff --git a/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.cc b/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.cc new file mode 100644 index 0000000..5fe3ea7 --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.cc @@ -0,0 +1,147 @@ +#include "tcircles3_audio_codec.h" + +#include +#include +#include + +#include "config.h" + +static const char TAG[] = "Tcircles3AudioCodec"; + +Tcircles3AudioCodec::Tcircles3AudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateVoiceHardware(mic_bclk, mic_ws, mic_data, spkr_bclk, spkr_lrclk, spkr_data); + + gpio_config_t config; + config.pin_bit_mask = BIT64(AUDIO_SPKR_ENABLE); + config.mode = GPIO_MODE_OUTPUT; + config.pull_up_en = GPIO_PULLUP_DISABLE; + config.pull_down_en = GPIO_PULLDOWN_ENABLE; + config.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER + config.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config); + gpio_set_level(AUDIO_SPKR_ENABLE, 0); + ESP_LOGI(TAG, "Tcircles3AudioCodec initialized"); +} + +Tcircles3AudioCodec::~Tcircles3AudioCodec() { + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Tcircles3AudioCodec::CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data) { + + i2s_chan_config_t mic_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(i2s_port_t(0), I2S_ROLE_MASTER); + mic_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + i2s_chan_config_t spkr_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(i2s_port_t(1), I2S_ROLE_MASTER); + spkr_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + + ESP_ERROR_CHECK(i2s_new_channel(&mic_chan_config, NULL, &rx_handle_)); + ESP_ERROR_CHECK(i2s_new_channel(&spkr_chan_config, &tx_handle_, NULL)); + + i2s_std_config_t mic_config = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = I2S_STD_PHILIPS_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_STEREO), + .gpio_cfg ={ + .mclk = I2S_GPIO_UNUSED, + .bclk = mic_bclk, + .ws = mic_ws, + .dout = I2S_GPIO_UNUSED, + .din = mic_data, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false, + } + } + }; + + i2s_std_config_t spkr_config = { + .clk_cfg ={ + .sample_rate_hz = static_cast(11025), + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = I2S_STD_PHILIPS_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_STEREO), + .gpio_cfg ={ + .mclk = I2S_GPIO_UNUSED, + .bclk = spkr_bclk, + .ws = spkr_lrclk, + .dout = spkr_data, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &mic_config)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &spkr_config)); + ESP_LOGI(TAG, "Voice hardware created"); +} + +void Tcircles3AudioCodec::SetOutputVolume(int volume) { + volume_ = volume; + AudioCodec::SetOutputVolume(volume); +} + +void Tcircles3AudioCodec::EnableInput(bool enable) { + AudioCodec::EnableInput(enable); +} + +void Tcircles3AudioCodec::EnableOutput(bool enable) { + if (enable){ + gpio_set_level(AUDIO_SPKR_ENABLE, 1); + }else{ + gpio_set_level(AUDIO_SPKR_ENABLE, 0); + } + AudioCodec::EnableOutput(enable); +} + +int Tcircles3AudioCodec::Read(int16_t *dest, int samples){ + if (input_enabled_){ + size_t bytes_read; + i2s_channel_read(rx_handle_, dest, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + } + return samples; +} + +int Tcircles3AudioCodec::Write(const int16_t *data, int samples){ + if (output_enabled_){ + size_t bytes_read; + auto output_data = (int16_t *)malloc(samples * sizeof(int16_t)); + for (size_t i = 0; i < samples; i++){ + output_data[i] = (float)data[i] * (float)(volume_ / 100.0); + } + i2s_channel_write(tx_handle_, output_data, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + free(output_data); + } + return samples; +} diff --git a/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.h b/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.h new file mode 100644 index 0000000..f68f818 --- /dev/null +++ b/main/boards/lilygo-t-circle-s3/tcircles3_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _TCIRCLES3_AUDIO_CODEC_H +#define _TCIRCLES3_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class Tcircles3AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t *data_if_ = nullptr; + const audio_codec_ctrl_if_t *out_ctrl_if_ = nullptr; + const audio_codec_if_t *out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t *in_ctrl_if_ = nullptr; + const audio_codec_if_t *in_codec_if_ = nullptr; + const audio_codec_gpio_if_t *gpio_if_ = nullptr; + + uint32_t volume_ = 70; + + void CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data,gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data); + + virtual int Read(int16_t *dest, int samples) override; + virtual int Write(const int16_t *data, int samples) override; + +public: + Tcircles3AudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference); + virtual ~Tcircles3AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/lilygo-t-display-p4/README.md b/main/boards/lilygo-t-display-p4/README.md new file mode 100644 index 0000000..9a236d8 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/README.md @@ -0,0 +1,42 @@ +## LILYGO T-Display-P4 + +The T-Display-P4 is a versatile development board based on the ESP32-P4 core. Its features include: + +1. **High Processing Power**: Equipped with the high-performance ESP32-P4 core processor, it can handle more complex graphics and video tasks, delivering smoother display performance. +2. **Low Power Design**: Offers multiple selectable power modes to effectively reduce energy consumption and extend battery life. +3. **High-Resolution Display**: Supports high resolution (default with a large MIPI interface screen at 540x1168px), providing sharp and clear visuals. +4. **Rich Peripheral Support**: Onboard peripherals include an HD MIPI touchscreen, ESP32-C6 module, speaker, microphone, LoRa module, GPS module, Ethernet, a linear vibration motor, an independent battery gauge for monitoring battery health and percentage, and an MIPI camera. Multiple GPIOs of both the ESP32-P4 and ESP32-C6 are exposed, enhancing the device's expandability. + +Official github: [T-Display-P4](https://github.com/Xinyuan-LilyGO/T-Display-P4) + +## Configuration + +### ESP32P4 Configuration + +* Set the compilation target to ESP32P4 + + idf.py set-target esp32p4 + +* Open menuconfig + + idf.py menuconfig + +* Select the board + + Xiaozhi Assistant -> Board Type -> LILYGO T-Display-P4 + +* Select the screen type + + Xiaozhi Assistant -> Select the screen type -> (Select the screen type you need to configure) + +* Screen the screen pixel format + + Xiaozhi Assistant -> Select the color format of the screen -> (Select the screen pixel format you need to configure) + +* Build + + idf.py build + +### ESP32C6 Configuration + +* Flash the slave example from the esp-hosted-mcu library for the target chip ESP32C6. The esp-hosted-mcu version must match the one used in the xiaozhi-esp32 library. \ No newline at end of file diff --git a/main/boards/lilygo-t-display-p4/config.h b/main/boards/lilygo-t-display-p4/config.h new file mode 100644 index 0000000..3e6b088 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/config.h @@ -0,0 +1,76 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#include "t_display_p4_config.h" + +#if defined CONFIG_SCREEN_PIXEL_FORMAT_RGB565 +#define SCREEN_BITS_PER_PIXEL 16 +#define SCREEN_COLOR_RGB_PIXEL_FORMAT LCD_COLOR_PIXEL_FORMAT_RGB565 +#define LVGL_COLOR_FORMAT LV_COLOR_FORMAT_RGB565 +#elif defined CONFIG_SCREEN_PIXEL_FORMAT_RGB888 +#define SCREEN_BITS_PER_PIXEL 24 +#define SCREEN_COLOR_RGB_PIXEL_FORMAT LCD_COLOR_PIXEL_FORMAT_RGB888 +#define LVGL_COLOR_FORMAT LV_COLOR_FORMAT_RGB888 +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + +// SCREEN +#if defined CONFIG_SCREEN_TYPE_HI8561 +#define SCREEN_WIDTH HI8561_SCREEN_WIDTH +#define SCREEN_HEIGHT HI8561_SCREEN_HEIGHT +#define SCREEN_MIPI_DSI_DPI_CLK_MHZ HI8561_SCREEN_MIPI_DSI_DPI_CLK_MHZ +#define SCREEN_MIPI_DSI_HSYNC HI8561_SCREEN_MIPI_DSI_HSYNC +#define SCREEN_MIPI_DSI_HBP HI8561_SCREEN_MIPI_DSI_HBP +#define SCREEN_MIPI_DSI_HFP HI8561_SCREEN_MIPI_DSI_HFP +#define SCREEN_MIPI_DSI_VSYNC HI8561_SCREEN_MIPI_DSI_VSYNC +#define SCREEN_MIPI_DSI_VBP HI8561_SCREEN_MIPI_DSI_VBP +#define SCREEN_MIPI_DSI_VFP HI8561_SCREEN_MIPI_DSI_VFP +#define SCREEN_DATA_LANE_NUM HI8561_SCREEN_DATA_LANE_NUM +#define SCREEN_LANE_BIT_RATE_MBPS HI8561_SCREEN_LANE_BIT_RATE_MBPS + +#elif defined CONFIG_SCREEN_TYPE_RM69A10 +#define SCREEN_WIDTH RM69A10_SCREEN_WIDTH +#define SCREEN_HEIGHT RM69A10_SCREEN_HEIGHT +#define SCREEN_MIPI_DSI_DPI_CLK_MHZ RM69A10_SCREEN_MIPI_DSI_DPI_CLK_MHZ +#define SCREEN_MIPI_DSI_HSYNC RM69A10_SCREEN_MIPI_DSI_HSYNC +#define SCREEN_MIPI_DSI_HBP RM69A10_SCREEN_MIPI_DSI_HBP +#define SCREEN_MIPI_DSI_HFP RM69A10_SCREEN_MIPI_DSI_HFP +#define SCREEN_MIPI_DSI_VSYNC RM69A10_SCREEN_MIPI_DSI_VSYNC +#define SCREEN_MIPI_DSI_VBP RM69A10_SCREEN_MIPI_DSI_VBP +#define SCREEN_MIPI_DSI_VFP RM69A10_SCREEN_MIPI_DSI_VFP +#define SCREEN_DATA_LANE_NUM RM69A10_SCREEN_DATA_LANE_NUM +#define SCREEN_LANE_BIT_RATE_MBPS RM69A10_SCREEN_LANE_BIT_RATE_MBPS + +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK static_cast(ES8311_MCLK) +#define AUDIO_I2S_GPIO_WS static_cast(ES8311_WS_LRCK) +#define AUDIO_I2S_GPIO_BCLK static_cast(ES8311_BCLK) +#define AUDIO_I2S_GPIO_DIN static_cast(ES8311_ADC_DATA) +#define AUDIO_I2S_GPIO_DOUT static_cast(ES8311_DAC_DATA) + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN static_cast(ES8311_SDA) +#define AUDIO_CODEC_I2C_SCL_PIN static_cast(ES8311_SCL) +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define SCREEN_SWAP_XY false +#define SCREEN_MIRROR_X false +#define SCREEN_MIRROR_Y false + +#define SCREEN_OFFSET_X 0 +#define SCREEN_OFFSET_Y 0 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lilygo-t-display-p4/hi8561_driver.cc b/main/boards/lilygo-t-display-p4/hi8561_driver.cc new file mode 100644 index 0000000..2d222b2 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/hi8561_driver.cc @@ -0,0 +1,404 @@ +/* + * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +#include "soc/soc_caps.h" + +#if SOC_MIPI_DSI_SUPPORTED +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_check.h" +#include "esp_lcd_panel_commands.h" +#include "esp_lcd_panel_interface.h" +#include "esp_lcd_panel_io.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_lcd_panel_vendor.h" +#include "esp_log.h" +#include "hi8561_driver.h" + +#define HI8561_PAD_CONTROL (0xB2) +#define HI8561_DSI_2_LANE (0x10) +#define HI8561_DSI_4_LANE (0x00) + +#define HI8561_CMD_SHLR_BIT (1ULL << 0) +#define HI8561_CMD_UPDN_BIT (1ULL << 1) +#define HI8561_MDCTL_VALUE_DEFAULT (0x01) + +static const hi8561_lcd_init_cmd_t vendor_specific_init_default[] = { + // {cmd, { data }, data_size, delay_ms} + /**** CMD_Page 3 ****/ + {0xDF, (uint8_t[]){0x90, 0x69, 0xF9}, 3, 0}, + {0xDE, (uint8_t[]){0x00}, 1, 0}, + {0xBB, (uint8_t[]){0x0F, 0x10, 0x43, 0x50, 0x32, 0x44, 0x44}, 7, 0}, + {0xBF, (uint8_t[]){0x46, 0x32}, 2, 0}, + {0xC0, (uint8_t[]){0x01, 0xAD, 0x01, 0xAD}, 4, 0}, + {0xBD, (uint8_t[]){0x00, 0xB4}, 2, 0}, + {0xC6, (uint8_t[]){0x00, 0x7D, 0x00, 0xC8, 0x00, 0x17, 0x1A, 0x82, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01}, 23, 0}, + {0xC8, (uint8_t[]){0x23, 0x48, 0x87}, 3, 0}, + // {0xCC, (uint8_t[]){0x33}, 1, 0},//4lane + {0xCC, (uint8_t[]){0x31}, 1, 0}, // 2lane + // {0xCC, (uint8_t[]){0x30}, 1, 0}, // 1lane + {0xBC, (uint8_t[]){0x2E, 0x80, 0x84}, 3, 0}, + {0xC3, (uint8_t[]){0x3B, 0x01, 0x02, 0x05, 0x0C, 0x0C, 0x75, 0x0A, 0x79, 0x0A, 0x79, 0x02, 0x6E, 0x02, 0x6E, 0x02, 0x6E, 0x0A, 0x0D, 0x0A, 0x0F, 0x0A, 0x0F, 0x0A, 0x0F}, 25, 0}, + {0xC4, (uint8_t[]){0x01, 0x02, 0x05, 0x0C, 0x0C, 0x75, 0x0A, 0x79, 0x0A, 0x79, 0x02, 0x6E, 0x02, 0x6E, 0x02, 0x6E, 0x0A, 0x0D, 0x0A, 0x0F, 0x0A, 0x0F, 0x0A, 0x0F}, 24, 0}, + {0xC5, (uint8_t[]){0x03, 0x05, 0x0C, 0x0C, 0x75, 0x0A, 0x79, 0x0A, 0x79, 0x02, 0x6E, 0x02, 0x6E, 0x02, 0x6E, 0x0A, 0x0D, 0x0A, 0x0F, 0x0A, 0x0F, 0x0A, 0x0F}, 23, 0}, + {0xD7, (uint8_t[]){0x00, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63, 0x0A, 0x63}, 17, 0}, + {0xCB, (uint8_t[]){0x7F, 0x78, 0x71, 0x64, 0x5A, 0x58, 0x4B, 0x51, 0x3A, 0x53, 0x51, 0x4F, 0x6A, 0x54, 0x57, 0x46, 0x3F, 0x2F, 0x1B, 0x0F, 0x08, 0x7F, 0x78, 0x71, 0x64, 0x5A, 0x58, 0x4B, 0x51, 0x3A, 0x53, 0x51, 0x4F, 0x6A, 0x54, 0x57, 0x46, 0x3F, 0x2F, 0x1B, 0x0F, 0x08, 0x00}, 43, 0}, + {0xCE, (uint8_t[]){0x00, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C}, 23, 0}, + {0xCF, (uint8_t[]){0x00, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 45, 0}, + {0xD0, (uint8_t[]){0x00, 0x1F, 0x1F, 0x11, 0x1E, 0x1F, 0x0F, 0x0F, 0x0D, 0x0D, 0x0B, 0x0B, 0x09, 0x09, 0x07, 0x07, 0x05, 0x05, 0x01, 0x1F, 0x1F, 0x1F, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 29, 0}, + {0xD1, (uint8_t[]){0x00, 0x1F, 0x1F, 0x10, 0x1E, 0x1F, 0x0E, 0x0E, 0x0C, 0x0C, 0x0A, 0x0A, 0x08, 0x08, 0x06, 0x06, 0x04, 0x04, 0x00, 0x1F, 0x1F, 0x1F, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 29, 0}, + {0xD2, (uint8_t[]){0x00, 0x5F, 0x1F, 0x10, 0x1F, 0x1E, 0x08, 0x08, 0x4A, 0x0A, 0x0C, 0x0C, 0x0E, 0x0E, 0x04, 0x04, 0x06, 0x06, 0x00, 0x1F, 0x1F, 0x1F, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 29, 0}, + {0xD3, (uint8_t[]){0x00, 0x1F, 0x1F, 0x11, 0x1F, 0x1E, 0x09, 0x09, 0x0B, 0x0B, 0x0D, 0x0D, 0x0F, 0x0F, 0x05, 0x05, 0x07, 0x07, 0x01, 0x1F, 0x1F, 0x1F, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 29, 0}, + {0xD4, (uint8_t[]){0x00, 0x20, 0x0B, 0x00, 0x0D, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x03, 0x03, 0x00, 0x81, 0x04, 0xAE, 0x04, 0xB0, 0x04, 0xB2, 0x04, 0xB4, 0x04, 0xB6, 0x04, 0xB8, 0x00, 0x00, 0x00, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x00, 0x06, 0x44, 0x06, 0x46, 0x03, 0x03, 0x00, 0x00, 0x07, 0x00, 0x06, 0x04, 0xA7, 0x04, 0xA8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00}, 87, 0}, + {0xD5, (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x07, 0x32, 0x5A, 0x00, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x1E, 0xB3, 0x00, 0x0F, 0x06, 0x0C, 0x00, 0x71, 0x20, 0x04, 0x10, 0x04, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}, 61, 0}, + {0xCD, (uint8_t[]){0x00, 0x00}, 2, 0}, + + {0xDE, (uint8_t[]){0x01}, 1, 0}, + {0xB9, (uint8_t[]){0x00, 0xFF, 0xFF, 0x04}, 4, 0}, + {0xC7, (uint8_t[]){0x1F, 0x14, 0x0E}, 3, 0}, + + {0xDE, (uint8_t[]){0x02}, 1, 0}, + {0xE5, (uint8_t[]){0x00, 0x60, 0x60, 0x02, 0x18, 0x60, 0x18, 0x60, 0x09, 0x04, 0x00, 0xC5, 0x01, 0x2C, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x04}, 24, 0}, + {0xE6, (uint8_t[]){0x10, 0x10, 0x82}, 3, 0}, + {0xC4, (uint8_t[]){0x00, 0x11, 0x07, 0x00, 0x11, 0x01, 0x08}, 7, 0}, + {0xC3, (uint8_t[]){0x20, 0xFF}, 2, 0}, + {0xBD, (uint8_t[]){0x1B}, 1, 0}, + {0xC6, (uint8_t[]){0x4A, 0x00}, 2, 0}, + {0xCD, (uint8_t[]){0x14, 0x64, 0x11, 0x40}, 4, 0}, + {0xC1, (uint8_t[]){0x00, 0x40, 0x00, 0x02, 0x02, 0x02, 0x02, 0x7F, 0x00, 0x00}, 10, 0}, + {0xB3, (uint8_t[]){0x00, 0xA8}, 2, 0}, + {0xBB, (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x40, 0x43, 0x04}, 11, 0}, + {0xC2, (uint8_t[]){0x02, 0x42, 0x50, 0x00, 0x02, 0xE4, 0x61, 0x73, 0xF9, 0x08}, 10, 0}, + {0xEC, (uint8_t[]){0x07, 0x07, 0x40, 0x00, 0x22, 0x02, 0x00, 0xFF, 0x08, 0x7C, 0x00, 0x00, 0x00, 0x00}, 14, 0}, + + {0xDE, (uint8_t[]){0x03}, 1, 0}, + {0xD1, (uint8_t[]){0x00, 0x00, 0x21, 0xFF, 0x00}, 5, 0}, + + {0xDE, (uint8_t[]){0x00}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 0, 30}, + + {0x11, (uint8_t[]){0x00}, 0, 120}, + + {0x29, (uint8_t[]){0x00}, 0, 50}, + + //============ Gamma END=========== +}; + +typedef struct +{ + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // save current value of LCD_CMD_MADCTL register + const hi8561_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + uint8_t lane_num; + struct + { + unsigned int reset_level : 1; + } flags; + // To save the original functions of MIPI DPI panel + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*init)(esp_lcd_panel_t *panel); +} hi8561_panel_t; + +static const char *TAG = "hi8561"; + +static esp_err_t panel_hi8561_send_init_cmds(hi8561_panel_t *hi8561); + +static esp_err_t panel_hi8561_del(esp_lcd_panel_t *panel); +static esp_err_t panel_hi8561_init(esp_lcd_panel_t *panel); +static esp_err_t panel_hi8561_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_hi8561_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_hi8561_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); +static esp_err_t panel_hi8561_sleep(esp_lcd_panel_t *panel, bool sleep); +static esp_err_t panel_hi8561_on_off(esp_lcd_panel_t *panel, bool on_off); + +esp_err_t esp_lcd_new_panel_hi8561(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + // ESP_LOGI(TAG, "version: %d.%d.%d", ESP_LCD_hi8561_VER_MAJOR, ESP_LCD_hi8561_VER_MINOR, + // ESP_LCD_hi8561_VER_PATCH); + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + hi8561_vendor_config_t *vendor_config = (hi8561_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->mipi_config.dpi_config && vendor_config->mipi_config.dsi_bus, ESP_ERR_INVALID_ARG, TAG, + "invalid vendor config"); + + esp_err_t ret = ESP_OK; + hi8561_panel_t *hi8561 = (hi8561_panel_t *)calloc(1, sizeof(hi8561_panel_t)); + ESP_RETURN_ON_FALSE(hi8561, ESP_ERR_NO_MEM, TAG, "no mem for hi8561 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_config_t io_conf = { + .pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num, + .mode = GPIO_MODE_OUTPUT, + }; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + hi8561->io = io; + hi8561->init_cmds = vendor_config->init_cmds; + hi8561->init_cmds_size = vendor_config->init_cmds_size; + hi8561->lane_num = vendor_config->mipi_config.lane_num; + hi8561->reset_gpio_num = panel_dev_config->reset_gpio_num; + hi8561->flags.reset_level = panel_dev_config->flags.reset_active_high; + hi8561->madctl_val = HI8561_MDCTL_VALUE_DEFAULT; + + // Create MIPI DPI panel + ESP_GOTO_ON_ERROR(esp_lcd_new_panel_dpi(vendor_config->mipi_config.dsi_bus, vendor_config->mipi_config.dpi_config, ret_panel), err, TAG, + "create MIPI DPI panel failed"); + ESP_LOGD(TAG, "new MIPI DPI panel @%p", *ret_panel); + + // Save the original functions of MIPI DPI panel + hi8561->del = (*ret_panel)->del; + hi8561->init = (*ret_panel)->init; + // Overwrite the functions of MIPI DPI panel + (*ret_panel)->del = panel_hi8561_del; + (*ret_panel)->init = panel_hi8561_init; + (*ret_panel)->reset = panel_hi8561_reset; + (*ret_panel)->mirror = panel_hi8561_mirror; + (*ret_panel)->invert_color = panel_hi8561_invert_color; + (*ret_panel)->disp_sleep = panel_hi8561_sleep; + (*ret_panel)->disp_on_off = panel_hi8561_on_off; + (*ret_panel)->user_data = hi8561; + + ESP_LOGD(TAG, "new hi8561 panel @%p", hi8561); + + return ESP_OK; + +err: + if (hi8561) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(static_cast(panel_dev_config->reset_gpio_num)); + } + free(hi8561); + } + return ret; +} + +static esp_err_t panel_hi8561_send_init_cmds(hi8561_panel_t *hi8561) +{ + esp_lcd_panel_io_handle_t io = hi8561->io; + const hi8561_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + // uint8_t lane_command = HI8561_DSI_2_LANE; + // bool is_cmd_overwritten = false; + + // switch (hi8561->lane_num) + // { + // case 0: + // case 2: + // lane_command = HI8561_DSI_2_LANE; + // break; + // case 4: + // lane_command = HI8561_DSI_4_LANE; + // break; + // default: + // ESP_LOGE(TAG, "Invalid lane number %d", hi8561->lane_num); + // return ESP_ERR_INVALID_ARG; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, HI8561_PAD_CONTROL, (uint8_t[]){ + // lane_command, + // }, + // 1), + // TAG, "send command failed"); + + // vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + // if (hi8561->init_cmds) + // { + // init_cmds = hi8561->init_cmds; + // init_cmds_size = hi8561->init_cmds_size; + // } + // else + // { + // init_cmds = vendor_specific_init_default; + // init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(hi8561_lcd_init_cmd_t); + // } + + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(hi8561_lcd_init_cmd_t); + + for (int i = 0; i < init_cmds_size; i++) + { + // // Check if the command has been used or conflicts with the internal + // if (init_cmds[i].data_bytes > 0) + // { + // switch (init_cmds[i].cmd) + // { + // case LCD_CMD_MADCTL: + // is_cmd_overwritten = true; + // hi8561->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + // break; + // default: + // is_cmd_overwritten = false; + // break; + // } + + // if (is_cmd_overwritten) + // { + // is_cmd_overwritten = false; + // ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + // init_cmds[i].cmd); + // } + // } + + esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + // printf("Ciallo\n"); + } + + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_hi8561_del(esp_lcd_panel_t *panel) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + + if (hi8561->reset_gpio_num >= 0) + { + gpio_reset_pin(static_cast(hi8561->reset_gpio_num)); + } + // Delete MIPI DPI panel + hi8561->del(panel); + ESP_LOGD(TAG, "del hi8561 panel @%p", hi8561); + free(hi8561); + + return ESP_OK; +} + +static esp_err_t panel_hi8561_init(esp_lcd_panel_t *panel) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + + ESP_RETURN_ON_ERROR(panel_hi8561_send_init_cmds(hi8561), TAG, "send init commands failed"); + ESP_RETURN_ON_ERROR(hi8561->init(panel), TAG, "init MIPI DPI panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_hi8561_reset(esp_lcd_panel_t *panel) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = hi8561->io; + + // Perform hardware reset + if (hi8561->reset_gpio_num >= 0) + { + gpio_set_level(static_cast(hi8561->reset_gpio_num), hi8561->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(static_cast(hi8561->reset_gpio_num), !hi8561->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(20)); + } + else if (io) + { // Perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(20)); + } + + return ESP_OK; +} + +static esp_err_t panel_hi8561_sleep(esp_lcd_panel_t *panel, bool sleep) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = hi8561->io; + + if (sleep == true) + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x10, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_hi8561 sleep on"); + } + else + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x11, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_hi8561 sleep off"); + } + + vTaskDelay(pdMS_TO_TICKS(120)); + + return ESP_OK; +} + +static esp_err_t panel_hi8561_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = hi8561->io; + + if (on_off == true) + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x29, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_hi8561 display on"); + } + else + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x28, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_hi8561 display off"); + } + + vTaskDelay(pdMS_TO_TICKS(120)); + + return ESP_OK; +} + +static esp_err_t panel_hi8561_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = hi8561->io; + uint8_t madctl_val = hi8561->madctl_val; + + ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + // Control mirror through LCD command + if (mirror_x) + { + madctl_val |= HI8561_CMD_SHLR_BIT; + } + else + { + madctl_val &= ~HI8561_CMD_SHLR_BIT; + } + if (mirror_y) + { + madctl_val |= HI8561_CMD_UPDN_BIT; + } + else + { + madctl_val &= ~HI8561_CMD_UPDN_BIT; + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){madctl_val}, 1), TAG, "send command failed"); + hi8561->madctl_val = madctl_val; + + return ESP_OK; +} + +static esp_err_t panel_hi8561_invert_color(esp_lcd_panel_t *panel, bool invert_color_data) +{ + hi8561_panel_t *hi8561 = (hi8561_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = hi8561->io; + uint8_t command = 0; + + ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + if (invert_color_data) + { + command = LCD_CMD_INVON; + } + else + { + command = LCD_CMD_INVOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + + return ESP_OK; +} + +#endif diff --git a/main/boards/lilygo-t-display-p4/hi8561_driver.h b/main/boards/lilygo-t-display-p4/hi8561_driver.h new file mode 100644 index 0000000..58429b8 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/hi8561_driver.h @@ -0,0 +1,66 @@ +/* + * @Description: hi8561_driver + * @Author: LILYGO_L + * @Date: 2025-06-13 11:02:44 + * @LastEditTime: 2025-10-09 10:36:27 + * @License: GPL 3.0 + */ +#pragma once + +#include +#include "soc/soc_caps.h" + +#if SOC_MIPI_DSI_SUPPORTED +#include "esp_lcd_panel_vendor.h" +#include "esp_lcd_mipi_dsi.h" + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct +{ + int cmd; /* +#include +#include +#include + +#include "cpp_bus_driver_library.h" +#include "hi8561_driver.h" +#include "rm69a10_driver.h" + +#define TAG "LilygoTDisplayP4Board" + +void TouchTask(void *arg); + +#if defined CONFIG_SCREEN_TYPE_HI8561 +class CustomBacklight : public Backlight { +private: + std::unique_ptr tool_; + +public: + CustomBacklight(std::unique_ptr tool) : tool_(std::move(tool)) {} + + void SetBrightnessImpl(uint8_t brightness) override{ + tool_->set_pwm_duty(brightness); + }; +}; +#elif defined CONFIG_SCREEN_TYPE_RM69A10 +class CustomBacklight : public Backlight { +private: + esp_lcd_panel_handle_t mipi_dpi_panel_; + +public: + CustomBacklight(esp_lcd_panel_handle_t panel) : mipi_dpi_panel_(panel) {} + + void SetBrightnessImpl(uint8_t brightness) override{ + set_rm69a10_brightness(mipi_dpi_panel_,static_cast(static_cast(brightness) * 2.55)); + }; +}; + +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + +class LilygoTDisplayP4Board : public WifiBoard { +public: + i2c_master_bus_handle_t audio_codec_i2c_bus_; + Button boot_button_; + LcdDisplay *display_; + esp_lcd_panel_handle_t mipi_dpi_panel_; + esp_timer_handle_t touchpad_timer_; + uint8_t brightness_; + + std::shared_ptr xl9535_iic_bus_ = std::make_shared(XL9535_SDA, XL9535_SCL, I2C_NUM_1); + std::unique_ptr xl9535_ = std::make_unique(xl9535_iic_bus_, XL9535_IIC_ADDRESS, DEFAULT_CPP_BUS_DRIVER_VALUE); + +#if defined CONFIG_SCREEN_TYPE_HI8561 + std::shared_ptr hi8561_t_iic_bus_ = std::make_shared(HI8561_TOUCH_SDA, HI8561_TOUCH_SCL, I2C_NUM_1); + std::unique_ptr hi8561_t_ = std::make_unique(hi8561_t_iic_bus_, HI8561_TOUCH_IIC_ADDRESS, DEFAULT_CPP_BUS_DRIVER_VALUE); + + std::unique_ptr hi8561_backlight_ = std::make_unique(); +#elif defined CONFIG_SCREEN_TYPE_RM69A10 + std::shared_ptr gt9895_iic_bus_ = std::make_shared(GT9895_TOUCH_SDA, GT9895_TOUCH_SCL, I2C_NUM_1); + std::unique_ptr gt9895_ = std::make_unique(gt9895_iic_bus_, GT9895_IIC_ADDRESS, GT9895_X_SCALE_FACTOR, GT9895_Y_SCALE_FACTOR, + DEFAULT_CPP_BUS_DRIVER_VALUE); +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + + std::unique_ptr esp32p4_ = std::make_unique(); + + bool Init_Ldo_Channel_Power(uint8_t chan_id, uint32_t voltage_mv){ + esp_ldo_channel_handle_t ldo_channel_handle = NULL; + esp_ldo_channel_config_t ldo_channel_config ={ + .chan_id = static_cast(chan_id), + .voltage_mv = static_cast(voltage_mv), + }; + if (esp_ldo_acquire_channel(&ldo_channel_config, &ldo_channel_handle) != ESP_OK){ + printf("esp_ldo_acquire_channel %d fail\n", chan_id); + return false; + } + + return true; + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &audio_codec_i2c_bus_)); + } + + void InitializeXl9535() { + xl9535_->begin(500000); + xl9535_->pin_mode(XL9535_ESP32P4_VCCA_POWER_EN, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_mode(XL9535_5_0_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_mode(XL9535_3_3_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + // 开关3.3v电压时候必须先将GPS断电 + xl9535_->pin_mode(XL9535_GPS_WAKE_UP, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_write(XL9535_GPS_WAKE_UP, Cpp_Bus_Driver::Xl95x5::Value::LOW); + // 开关3.3v电压时候必须先将ESP32C6断电 + xl9535_->pin_mode(XL9535_ESP32C6_EN, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_write(XL9535_ESP32C6_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + + xl9535_->pin_write(XL9535_ESP32P4_VCCA_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + + xl9535_->pin_write(XL9535_5_0_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_5_0_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_5_0_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + + xl9535_->pin_write(XL9535_3_3_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_3_3_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_3_3_V_POWER_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(10)); + + // ESP32C6复位 + xl9535_->pin_write(XL9535_ESP32C6_EN, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(100)); + xl9535_->pin_write(XL9535_ESP32C6_EN, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(100)); + xl9535_->pin_write(XL9535_ESP32C6_EN, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(100)); + + vTaskDelay(pdMS_TO_TICKS(1000)); + } + + void InitializeLCD() { + xl9535_->pin_mode(XL9535_SCREEN_RST, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_write(XL9535_SCREEN_RST, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_SCREEN_RST, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_SCREEN_RST, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + + Init_Ldo_Channel_Power(3, 1800); + + esp_lcd_panel_io_handle_t mipi_dbi_io = NULL; + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = SCREEN_DATA_LANE_NUM, + .lane_bit_rate_mbps = SCREEN_LANE_BIT_RATE_MBPS, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_io_config = { + .virtual_channel = 0, + .lcd_cmd_bits = 8, // according to the LCD spec + .lcd_param_bits = 8, // according to the LCD spec + }; + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_io_config, &mipi_dbi_io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .virtual_channel = 0, + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = SCREEN_MIPI_DSI_DPI_CLK_MHZ, + .pixel_format = SCREEN_COLOR_RGB_PIXEL_FORMAT, + .num_fbs = 0, + .video_timing = { + .h_size = SCREEN_WIDTH, + .v_size = SCREEN_HEIGHT, + .hsync_pulse_width = SCREEN_MIPI_DSI_HSYNC, + .hsync_back_porch = SCREEN_MIPI_DSI_HBP, + .hsync_front_porch = SCREEN_MIPI_DSI_HFP, + .vsync_pulse_width = SCREEN_MIPI_DSI_VSYNC, + .vsync_back_porch = SCREEN_MIPI_DSI_VBP, + .vsync_front_porch = SCREEN_MIPI_DSI_VFP, + }, + .flags = { + .use_dma2d = true, // use DMA2D to copy draw buffer into frame buffer + } + }; + +#if defined CONFIG_SCREEN_TYPE_HI8561 + hi8561_vendor_config_t vendor_config = { + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + }, + }; + esp_lcd_panel_dev_config_t dev_config = { + .reset_gpio_num = -1, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = SCREEN_BITS_PER_PIXEL, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_hi8561(mipi_dbi_io, &dev_config, &mipi_dpi_panel_); + #elif defined CONFIG_SCREEN_TYPE_RM69A10 + rm69a10_vendor_config_t vendor_config = { + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + }, + }; + esp_lcd_panel_dev_config_t dev_config = { + .reset_gpio_num = -1, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = SCREEN_BITS_PER_PIXEL, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_rm69a10(mipi_dbi_io, &dev_config, &mipi_dpi_panel_); +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + + esp_lcd_panel_init(mipi_dpi_panel_); + +#if defined CONFIG_SCREEN_TYPE_HI8561 + hi8561_backlight_->create_pwm(HI8561_SCREEN_BL, ledc_channel_t::LEDC_CHANNEL_0, 2000); +#elif defined CONFIG_SCREEN_TYPE_RM69A10 +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + + + display_ = new MipiLcdDisplay(mipi_dbi_io, mipi_dpi_panel_, SCREEN_WIDTH, SCREEN_HEIGHT, + SCREEN_OFFSET_X, SCREEN_OFFSET_Y, SCREEN_MIRROR_X, SCREEN_MIRROR_Y, SCREEN_SWAP_XY); + } + + void InitializeTouch(){ + xl9535_->pin_mode(XL9535_TOUCH_RST, Cpp_Bus_Driver::Xl95x5::Mode::OUTPUT); + xl9535_->pin_write(XL9535_TOUCH_RST, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_TOUCH_RST, Cpp_Bus_Driver::Xl95x5::Value::LOW); + vTaskDelay(pdMS_TO_TICKS(10)); + xl9535_->pin_write(XL9535_TOUCH_RST, Cpp_Bus_Driver::Xl95x5::Value::HIGH); + vTaskDelay(pdMS_TO_TICKS(10)); + +#if defined CONFIG_SCREEN_TYPE_HI8561 + hi8561_t_iic_bus_->set_bus_handle(xl9535_iic_bus_->get_bus_handle()); + hi8561_t_->begin(); +#elif defined CONFIG_SCREEN_TYPE_RM69A10 + gt9895_iic_bus_->set_bus_handle(xl9535_iic_bus_->get_bus_handle()); + gt9895_->begin(); +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + + xTaskCreate(TouchTask, "tp", 2 * 1024, this, 5, NULL); + } + + void AppToggleChatState(void){ + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + AppToggleChatState(); + }); + } + + LilygoTDisplayP4Board() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeXl9535(); + InitializeLCD(); + InitializeTouch(); + InitializeButtons(); + GetBacklight()->SetBrightness(100); + } + + virtual AudioCodec *GetAudioCodec() override { + static Es8311AudioCodec audio_codec(audio_codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + +#if defined CONFIG_SCREEN_TYPE_HI8561 + virtual Backlight* GetBacklight() override { + static CustomBacklight backlight(std::move(hi8561_backlight_)); + return &backlight; + } +#elif defined CONFIG_SCREEN_TYPE_RM69A10 + virtual Backlight* GetBacklight() override { + static CustomBacklight backlight(std::move(mipi_dpi_panel_)); + return &backlight; + } +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + +}; + +void TouchTask(void *arg) { + LilygoTDisplayP4Board* board = (LilygoTDisplayP4Board*)arg; + + static bool touch_flag = false; + static bool touch_lock_flag = true; + static size_t first_touch_time = 0; + static bool waiting_for_second_tap = false; + + while (1){ +#if defined CONFIG_SCREEN_TYPE_HI8561 + if (board->hi8561_t_->get_finger_count() > 0){ + if(touch_flag == false){ + touch_lock_flag = false; + } + touch_flag = true; + } else { + touch_flag = false; + } +#elif defined CONFIG_SCREEN_TYPE_RM69A10 + if (board->gt9895_->get_finger_count() > 0){ + if(touch_flag == false){ + touch_lock_flag = false; + } + touch_flag = true; + } else { + touch_flag = false; + } +#else +#error "unknown macro definition, please select the correct macro definition." +#endif + + if(touch_lock_flag == false){ + size_t current_time = board->esp32p4_->get_system_time_ms(); + + if (!waiting_for_second_tap) { + // 第一次点击 + first_touch_time = current_time; + waiting_for_second_tap = true; + printf("first touch detected, waiting for second...\n"); + } else { + // 第二次点击,检查时间间隔 + // 500ms内完成双击 + if ((current_time - first_touch_time) <= 500) { + printf("double touch trigger\n"); + + board->AppToggleChatState(); + + // 重置状态 + waiting_for_second_tap = false; + first_touch_time = 0; + } else { + // 超时,重新开始 + first_touch_time = current_time; + printf("first touch timeout, restart...\n"); + } + } + + touch_lock_flag = true; + } + + // 处理双击超时 + if (waiting_for_second_tap) { + size_t current_time = board->esp32p4_->get_system_time_ms(); + + if ((current_time - first_touch_time) > 500) { + waiting_for_second_tap = false; + first_touch_time = 0; + printf("double touch timeout\n"); + } + } + + vTaskDelay(pdMS_TO_TICKS(50)); + } +} + +DECLARE_BOARD(LilygoTDisplayP4Board); diff --git a/main/boards/lilygo-t-display-p4/rm69a10_driver.cc b/main/boards/lilygo-t-display-p4/rm69a10_driver.cc new file mode 100644 index 0000000..cc6b329 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/rm69a10_driver.cc @@ -0,0 +1,377 @@ +/* + * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +#include "soc/soc_caps.h" + +#if SOC_MIPI_DSI_SUPPORTED +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_check.h" +#include "esp_lcd_panel_commands.h" +#include "esp_lcd_panel_interface.h" +#include "esp_lcd_panel_io.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_lcd_panel_vendor.h" +#include "esp_log.h" +#include "rm69a10_driver.h" + +#define RM69A10_PAD_CONTROL (0xB2) +#define RM69A10_DSI_2_LANE (0x10) +#define RM69A10_DSI_4_LANE (0x00) + +#define RM69A10_CMD_SHLR_BIT (1ULL << 0) +#define RM69A10_CMD_UPDN_BIT (1ULL << 1) +#define RM69A10_MDCTL_VALUE_DEFAULT (0x01) + +static const rm69a10_lcd_init_cmd_t vendor_specific_init_default[] = { + // {cmd, { data }, data_size, delay_ms} + /**** CMD_Page 3 ****/ + {0xFE, (uint8_t[]){0xFD}, 1, 0}, + {0x80, (uint8_t[]){0xFC}, 1, 0}, + {0xFE, (uint8_t[]){0x00}, 1, 0}, + {0x2A, (uint8_t[]){0x00, 0x00, 0x02, 0x37}, 4, 0}, + {0x2B, (uint8_t[]){0x00, 0x00, 0x04, 0xCF}, 4, 0}, + {0x31, (uint8_t[]){0x00, 0x03, 0x02, 0x34}, 4, 0}, + {0x30, (uint8_t[]){0x00, 0x00, 0x04, 0xCF}, 4, 0}, + {0x12, (uint8_t[]){0x00}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 1, 0}, +#if CONFIG_SCREEN_PIXEL_FORMAT_RGB565 + {0x3A, (uint8_t[]){0x75}, 1, 0}, // interface pixel format 16bit/pixel +#elif CONFIG_SCREEN_PIXEL_FORMAT_RGB888 + {0x3A, (uint8_t[]){0x77}, 1, 0}, // interface pixel format 24bit/pixel +#endif + // {0x51, (uint8_t[]){0xFE}, 1, 0}, + {0x51, (uint8_t[]){0x00}, 1, 0}, // 设置屏幕亮度为0 + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0x29, (uint8_t[]){0x00}, 0, 0}, + //============ Gamma END=========== +}; + +typedef struct +{ + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // save current value of LCD_CMD_MADCTL register + const rm69a10_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + uint8_t lane_num; + struct + { + unsigned int reset_level : 1; + } flags; + // To save the original functions of MIPI DPI panel + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*init)(esp_lcd_panel_t *panel); +} rm69a10_panel_t; + +static const char *TAG = "rm69a10"; + +static esp_err_t panel_rm69a10_send_init_cmds(rm69a10_panel_t *rm69a10); + +static esp_err_t panel_rm69a10_del(esp_lcd_panel_t *panel); +static esp_err_t panel_rm69a10_init(esp_lcd_panel_t *panel); +static esp_err_t panel_rm69a10_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_rm69a10_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_rm69a10_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); +static esp_err_t panel_rm69a10_sleep(esp_lcd_panel_t *panel, bool sleep); +static esp_err_t panel_rm69a10_on_off(esp_lcd_panel_t *panel, bool on_off); + +esp_err_t esp_lcd_new_panel_rm69a10(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + // ESP_LOGI(TAG, "version: %d.%d.%d", ESP_LCD_RM69A10_VER_MAJOR, ESP_LCD_RM69A10_VER_MINOR, + // ESP_LCD_RM69A10_VER_PATCH); + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + rm69a10_vendor_config_t *vendor_config = (rm69a10_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->mipi_config.dpi_config && vendor_config->mipi_config.dsi_bus, ESP_ERR_INVALID_ARG, TAG, + "invalid vendor config"); + + esp_err_t ret = ESP_OK; + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)calloc(1, sizeof(rm69a10_panel_t)); + ESP_RETURN_ON_FALSE(rm69a10, ESP_ERR_NO_MEM, TAG, "no mem for rm69a10 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_config_t io_conf = { + .pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num, + .mode = GPIO_MODE_OUTPUT, + }; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + rm69a10->io = io; + rm69a10->init_cmds = vendor_config->init_cmds; + rm69a10->init_cmds_size = vendor_config->init_cmds_size; + rm69a10->lane_num = vendor_config->mipi_config.lane_num; + rm69a10->reset_gpio_num = panel_dev_config->reset_gpio_num; + rm69a10->flags.reset_level = panel_dev_config->flags.reset_active_high; + rm69a10->madctl_val = RM69A10_MDCTL_VALUE_DEFAULT; + + // Create MIPI DPI panel + ESP_GOTO_ON_ERROR(esp_lcd_new_panel_dpi(vendor_config->mipi_config.dsi_bus, vendor_config->mipi_config.dpi_config, ret_panel), err, TAG, + "create MIPI DPI panel failed"); + ESP_LOGD(TAG, "new MIPI DPI panel @%p", *ret_panel); + + // Save the original functions of MIPI DPI panel + rm69a10->del = (*ret_panel)->del; + rm69a10->init = (*ret_panel)->init; + // Overwrite the functions of MIPI DPI panel + (*ret_panel)->del = panel_rm69a10_del; + (*ret_panel)->init = panel_rm69a10_init; + (*ret_panel)->reset = panel_rm69a10_reset; + (*ret_panel)->mirror = panel_rm69a10_mirror; + (*ret_panel)->invert_color = panel_rm69a10_invert_color; + (*ret_panel)->disp_sleep = panel_rm69a10_sleep; + (*ret_panel)->disp_on_off = panel_rm69a10_on_off; + (*ret_panel)->user_data = rm69a10; + ESP_LOGD(TAG, "new rm69a10 panel @%p", rm69a10); + + return ESP_OK; + +err: + if (rm69a10) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(static_cast(panel_dev_config->reset_gpio_num)); + } + free(rm69a10); + } + return ret; +} + +static esp_err_t panel_rm69a10_send_init_cmds(rm69a10_panel_t *rm69a10) +{ + esp_lcd_panel_io_handle_t io = rm69a10->io; + const rm69a10_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + // uint8_t lane_command = RM69A10_DSI_2_LANE; + // bool is_cmd_overwritten = false; + + // switch (rm69a10->lane_num) + // { + // case 0: + // case 2: + // lane_command = RM69A10_DSI_2_LANE; + // break; + // case 4: + // lane_command = RM69A10_DSI_4_LANE; + // break; + // default: + // ESP_LOGE(TAG, "Invalid lane number %d", rm69a10->lane_num); + // return ESP_ERR_INVALID_ARG; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, RM69A10_PAD_CONTROL, (uint8_t[]){ + // lane_command, + // }, + // 1), + // TAG, "send command failed"); + + // vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + // if (rm69a10->init_cmds) + // { + // init_cmds = rm69a10->init_cmds; + // init_cmds_size = rm69a10->init_cmds_size; + // } + // else + // { + // init_cmds = vendor_specific_init_default; + // init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(rm69a10_lcd_init_cmd_t); + // } + + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(rm69a10_lcd_init_cmd_t); + + for (int i = 0; i < init_cmds_size; i++) + { + // // Check if the command has been used or conflicts with the internal + // if (init_cmds[i].data_bytes > 0) + // { + // switch (init_cmds[i].cmd) + // { + // case LCD_CMD_MADCTL: + // is_cmd_overwritten = true; + // rm69a10->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + // break; + // default: + // is_cmd_overwritten = false; + // break; + // } + + // if (is_cmd_overwritten) + // { + // is_cmd_overwritten = false; + // ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + // init_cmds[i].cmd); + // } + // } + + // Send command + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + // printf("Ciallo\n"); + } + + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_del(esp_lcd_panel_t *panel) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + + if (rm69a10->reset_gpio_num >= 0) + { + gpio_reset_pin(static_cast(rm69a10->reset_gpio_num)); + } + // Delete MIPI DPI panel + rm69a10->del(panel); + ESP_LOGD(TAG, "del rm69a10 panel @%p", rm69a10); + free(rm69a10); + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_init(esp_lcd_panel_t *panel) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + + ESP_RETURN_ON_ERROR(panel_rm69a10_send_init_cmds(rm69a10), TAG, "send init commands failed"); + ESP_RETURN_ON_ERROR(rm69a10->init(panel), TAG, "init MIPI DPI panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_reset(esp_lcd_panel_t *panel) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + + // Perform hardware reset + if (rm69a10->reset_gpio_num >= 0) + { + gpio_set_level(static_cast(rm69a10->reset_gpio_num), rm69a10->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(static_cast(rm69a10->reset_gpio_num), !rm69a10->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(20)); + } + else if (io) + { // Perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(20)); + } + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_sleep(esp_lcd_panel_t *panel, bool sleep) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + + if (sleep == true) + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x10, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_rm69a10 sleep on"); + } + else + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x11, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_rm69a10 sleep off"); + } + + vTaskDelay(pdMS_TO_TICKS(120)); + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + + if (on_off == true) + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x29, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_rm69a10 display on"); + } + else + { + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x28, 0x00, 0), TAG, "esp_lcd_panel_io_tx_param fail"); + ESP_LOGI(TAG, "panel_rm69a10 display off"); + } + + vTaskDelay(pdMS_TO_TICKS(120)); + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + uint8_t madctl_val = rm69a10->madctl_val; + + ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + // Control mirror through LCD command + if (mirror_x) + { + madctl_val |= RM69A10_CMD_SHLR_BIT; + } + else + { + madctl_val &= ~RM69A10_CMD_SHLR_BIT; + } + if (mirror_y) + { + madctl_val |= RM69A10_CMD_UPDN_BIT; + } + else + { + madctl_val &= ~RM69A10_CMD_UPDN_BIT; + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){madctl_val}, 1), TAG, "send command failed"); + rm69a10->madctl_val = madctl_val; + + return ESP_OK; +} + +static esp_err_t panel_rm69a10_invert_color(esp_lcd_panel_t *panel, bool invert_color_data) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + uint8_t command = 0; + + ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + if (invert_color_data) + { + command = LCD_CMD_INVON; + } + else + { + command = LCD_CMD_INVOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + + return ESP_OK; +} + +esp_err_t set_rm69a10_brightness(esp_lcd_panel_t *panel, uint8_t brightness) +{ + rm69a10_panel_t *rm69a10 = (rm69a10_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = rm69a10->io; + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, 0x51, &brightness, 1), TAG, "esp_lcd_panel_io_tx_param fail"); + + return ESP_OK; +} + +#endif diff --git a/main/boards/lilygo-t-display-p4/rm69a10_driver.h b/main/boards/lilygo-t-display-p4/rm69a10_driver.h new file mode 100644 index 0000000..e525bd4 --- /dev/null +++ b/main/boards/lilygo-t-display-p4/rm69a10_driver.h @@ -0,0 +1,68 @@ +/* + * @Description: rm69a10_driver + * @Author: LILYGO_L + * @Date: 2025-07-07 14:23:16 + * @LastEditTime: 2025-10-09 10:36:33 + * @License: GPL 3.0 + */ +#pragma once + +#include +#include "soc/soc_caps.h" + +#if SOC_MIPI_DSI_SUPPORTED +#include "esp_lcd_panel_vendor.h" +#include "esp_lcd_mipi_dsi.h" + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct +{ + int cmd; /*(RM69A10_SCREEN_WIDTH) / static_cast(GT9895_MAX_X_SIZE) +#define GT9895_Y_SCALE_FACTOR static_cast(RM69A10_SCREEN_HEIGHT) / static_cast(GT9895_MAX_Y_SIZE) + +// CAMERA +#define CAMERA_WIDTH 1920 +#define CAMERA_HEIGHT 1080 +// #define CAMERA_WIDTH 1280 +// #define CAMERA_HEIGHT 720 +// #define CAMERA_WIDTH 800 +// #define CAMERA_HEIGHT 800 +// #define CAMERA_WIDTH 640 +// #define CAMERA_HEIGHT 480 + +#define CAMERA_DATA_LANE_NUM 2 +#define CAMERA_LANE_BIT_RATE_MBPS 1000 +#define CAMERA_MIPI_DSI_DPI_CLK_MHZ 60 + +// SD +#define SD_BASE_PATH "/sdcard" + +////////////////////////////////////////////////// other define config ////////////////////////////////////////////////// \ No newline at end of file diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/README.md b/main/boards/lilygo-t-display-s3-pro-mvsrlora/README.md new file mode 100644 index 0000000..c3b8d0e --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/README.md @@ -0,0 +1,32 @@ +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> LILYGO T-Display-S3-Pro-MVSRLora +Or +Xiaozhi Assistant -> Board Type -> LILYGO T-Display-S3-Pro-MVSRLora_NO_BATTERY +``` + + +**编译:** + +```bash +idf.py build +``` + +LILYGO T-Display-S3-Pro +
+LILYGO T-Display-S3-Pro-MVSRLora \ No newline at end of file diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.h b/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.h new file mode 100644 index 0000000..44c0a03 --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include "pin_config.h" + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_MIC_I2S_GPIO_BCLK GPIO_NUM_NC +#define AUDIO_MIC_I2S_GPIO_WS static_cast(MP34DT05TR_LRCLK) +#define AUDIO_MIC_I2S_GPIO_DATA static_cast(MP34DT05TR_DATA) +#define AUDIO_MIC_ENABLE static_cast(MP34DT05TR_EN) + +#define AUDIO_SPKR_I2S_GPIO_BCLK static_cast(MAX98357A_BCLK) +#define AUDIO_SPKR_I2S_GPIO_LRCLK static_cast(MAX98357A_LRCLK) +#define AUDIO_SPKR_I2S_GPIO_DATA static_cast(MAX98357A_DATA) +#define AUDIO_SPKR_ENABLE static_cast(MAX98357A_EN) + +#define TOUCH_I2C_SDA_PIN static_cast(TOUCH_IIC_SDA) +#define TOUCH_I2C_SCL_PIN static_cast(TOUCH_IIC_SCL) + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_WIDTH LCD_WIDTH +#define DISPLAY_HEIGHT LCD_HEIGHT +#define DISPLAY_MOSI LCD_MOSI +#define DISPLAY_SCLK LCD_SCLK +#define DISPLAY_DC LCD_DC +#define DISPLAY_RST LCD_RST +#define DISPLAY_CS LCD_CS +#define DISPLAY_BL static_cast(LCD_BL) +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN DISPLAY_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.json b/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.json new file mode 100644 index 0000000..f7e4505 --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "lilygo-t-display-s3-pro-mvsrlora", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/lilygo-t-display-s3-pro-mvsrlora.cc b/main/boards/lilygo-t-display-s3-pro-mvsrlora/lilygo-t-display-s3-pro-mvsrlora.cc new file mode 100644 index 0000000..f0a4aed --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/lilygo-t-display-s3-pro-mvsrlora.cc @@ -0,0 +1,283 @@ +#include "wifi_board.h" +#include "tdisplays3promvsrlora_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "i2c_device.h" + +#include +#include +#include +#include +#include +#include "esp_lcd_st7796.h" + +#define TAG "LilygoTDisplays3ProMVSRLoraBoard" + +class Cst2xxse : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + Cst2xxse(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0x06); + ESP_LOGI(TAG, "Get cst2xxse chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Cst2xxse() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x00, read_buffer_, 6); + tp_.num = read_buffer_[5] & 0x0F; + tp_.x = (static_cast(read_buffer_[1]) << 4) | (read_buffer_[3] & 0xF0); + tp_.y = (static_cast(read_buffer_[2]) << 4) | (read_buffer_[3] & 0x0F); + // ESP_LOGI(TAG, "Touch num: %d x: %d y: %d", tp_.num,tp_.x,tp_.y); + } + + const TouchPoint_t &GetTouchPoint() { + return tp_; + } + +private: + uint8_t *read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class Sy6970 : public I2cDevice { +public: + + Sy6970(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0x14); + ESP_LOGI(TAG, "Get sy6970 chip ID: 0x%02X", (chip_id & 0B00111000)); + + WriteReg(0x00,0B00001000); // Disable ILIM pin + WriteReg(0x02,0B11011101); // Enable ADC measurement function + WriteReg(0x07,0B10001101); // Disable watchdog timer feeding function + + #ifdef CONFIG_BOARD_TYPE_LILYGO_T_DISPLAY_S3_PRO_MVSRLORA_NO_BATTERY + WriteReg(0x09,0B01100100); // Disable BATFET when battery is not needed + #endif + } +}; + +class LilygoTDisplays3ProMVSRLoraBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Cst2xxse *cst226se_; + Sy6970 *sy6970_; + LcdDisplay *display_; + Button boot_button_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitI2c(){ + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_config = { + .i2c_port = I2C_NUM_0, + .sda_io_num = TOUCH_I2C_SDA_PIN, + .scl_io_num = TOUCH_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + } + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_config, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + static void touchpad_daemon(void *param) { + vTaskDelay(pdMS_TO_TICKS(2000)); + auto &board = (LilygoTDisplays3ProMVSRLoraBoard&)Board::GetInstance(); + auto touchpad = board.GetTouchpad(); + bool was_touched = false; + while (1) { + touchpad->UpdateTouchPoint(); + if (touchpad->GetTouchPoint().num > 0){ + // On press + if (!was_touched) { + was_touched = true; + Application::GetInstance().ToggleChatState(); + } + } + // On release + else if (was_touched) { + was_touched = false; + } + vTaskDelay(pdMS_TO_TICKS(50)); + } + vTaskDelete(NULL); + } + + void InitCst226se() { + ESP_LOGI(TAG, "Init Cst2xxse"); + cst226se_ = new Cst2xxse(i2c_bus_, 0x5A); + xTaskCreate(touchpad_daemon, "tp", 4096, NULL, 5, NULL); + } + + void InitSy6970() { + ESP_LOGI(TAG, "Init Sy6970"); + sy6970_ = new Sy6970(i2c_bus_, 0x6A); + } + + void InitSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitSt7796Display() { + ESP_LOGI(TAG, "Init St7796"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7796(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, false)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_set_gap(panel, 49, 0)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + gpio_config_t config; + config.pin_bit_mask = BIT64(DISPLAY_BL); + config.mode = GPIO_MODE_OUTPUT; + config.pull_up_en = GPIO_PULLUP_DISABLE; + config.pull_down_en = GPIO_PULLDOWN_ENABLE; + config.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER + config.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config); + gpio_set_level(DISPLAY_BL, 0); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + power_save_timer_->WakeUp(); + app.ToggleChatState(); + }); + } + +public: + LilygoTDisplays3ProMVSRLoraBoard() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitI2c(); + I2cDetect(); + InitCst226se(); + InitSy6970(); + InitSpi(); + InitSt7796Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Tdisplays3promvsrloraAudioCodec audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_MIC_I2S_GPIO_BCLK, + AUDIO_MIC_I2S_GPIO_WS, + AUDIO_MIC_I2S_GPIO_DATA, + AUDIO_SPKR_I2S_GPIO_BCLK, + AUDIO_SPKR_I2S_GPIO_LRCLK, + AUDIO_SPKR_I2S_GPIO_DATA, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override{ + return display_; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst2xxse *GetTouchpad() { + return cst226se_; + } +}; + +DECLARE_BOARD(LilygoTDisplays3ProMVSRLoraBoard); diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/pin_config.h b/main/boards/lilygo-t-display-s3-pro-mvsrlora/pin_config.h new file mode 100644 index 0000000..0b952d5 --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/pin_config.h @@ -0,0 +1,80 @@ +/* + * @Description: None + * @Author: None + * @Date: 2023-08-16 14:24:03 + * @LastEditTime: 2025-04-23 11:25:00 + * @License: GPL 3.0 + */ +#pragma once + +// ST7796 +#define LCD_WIDTH 222 +#define LCD_HEIGHT 480 +#define LCD_BL 48 +#define LCD_MOSI 17 +#define LCD_MISO 8 +#define LCD_SCLK 18 +#define LCD_CS 39 +#define LCD_DC 9 +#define LCD_RST 47 + +// IIC +#define IIC_SDA 5 +#define IIC_SCL 6 + +// CST226SE +#define CST226SE_IIC_ADDRESS 0x5A +#define TOUCH_RST 13 +#define TOUCH_INT 21 +#define TOUCH_IIC_SDA IIC_SDA +#define TOUCH_IIC_SCL IIC_SCL + +// SY6970 +#define SY6970_SDA 5 +#define SY6970_SCL 6 +#define SY6970_Address 0x6A +#define SY6970_INT 21 + +// SD +#define SD_CS 14 +#define SD_MISO 8 +#define SD_MOSI 17 +#define SD_SCLK 18 + +// RT9080 +#define RT9080_EN 42 + +// MAX98357A +#define MAX98357A_BCLK 4 +#define MAX98357A_LRCLK 15 +#define MAX98357A_DATA 11 +#define MAX98357A_EN 41 + +// Vibration Motor +#define VIBRATINO_MOTOR_PWM 45 + +// PCF85063 +#define PCF85063_IIC_SDA 5 +#define PCF85063_IIC_SCL 6 +#define PCF85063_INT 21 + +// LR1121 +#define LR1121_BUSY 46 +#define LR1121_INT 40 +#define LR1121_SCLK 18 +#define LR1121_MOSI 17 +#define LR1121_MISO 8 +#define LR1121_CS 7 +#define LR1121_RST 10 + +// ICM20948 +#define ICM20948_ADDRESS 0x28 +#define ICM20948_SDA 5 +#define ICM20948_SCL 6 +#define ICM20948_INT 21 + +// MP34DT05TRF +#define MP34DT05TR_LRCLK 1 +#define MP34DT05TR_DATA 2 +#define MP34DT05TR_EN 3 + diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.cc b/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.cc new file mode 100644 index 0000000..0beec45 --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.cc @@ -0,0 +1,150 @@ +#include "tdisplays3promvsrlora_audio_codec.h" + +#include +#include +#include +#include + +#include "config.h" + +static const char TAG[] = "Tdisplays3promvsrloraAudioCodec"; + +Tdisplays3promvsrloraAudioCodec::Tdisplays3promvsrloraAudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateVoiceHardware(mic_bclk, mic_ws, mic_data, spkr_bclk, spkr_lrclk, spkr_data); + + gpio_config_t config_mic_en; + config_mic_en.pin_bit_mask = BIT64(AUDIO_MIC_ENABLE); + config_mic_en.mode = GPIO_MODE_OUTPUT; + config_mic_en.pull_up_en = GPIO_PULLUP_ENABLE; + config_mic_en.pull_down_en = GPIO_PULLDOWN_DISABLE; + config_mic_en.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER +config_mic_en.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config_mic_en); + gpio_set_level(AUDIO_MIC_ENABLE, 1); + + gpio_config_t config_spkr_en; + config_spkr_en.pin_bit_mask = BIT64(AUDIO_SPKR_ENABLE); + config_spkr_en.mode = GPIO_MODE_OUTPUT; + config_spkr_en.pull_up_en = GPIO_PULLUP_DISABLE; + config_spkr_en.pull_down_en = GPIO_PULLDOWN_ENABLE; + config_spkr_en.intr_type = GPIO_INTR_DISABLE; +#if SOC_GPIO_SUPPORT_PIN_HYS_FILTER +config_spkr_en.hys_ctrl_mode = GPIO_HYS_SOFT_ENABLE; +#endif + gpio_config(&config_spkr_en); + gpio_set_level(AUDIO_SPKR_ENABLE, 0); + + ESP_LOGI(TAG, "Tdisplays3promvsrloraAudioCodec initialized"); +} + +Tdisplays3promvsrloraAudioCodec::~Tdisplays3promvsrloraAudioCodec() { + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Tdisplays3promvsrloraAudioCodec::CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data) { + + i2s_chan_config_t mic_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(i2s_port_t(0), I2S_ROLE_MASTER); + mic_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + i2s_chan_config_t spkr_chan_config = I2S_CHANNEL_DEFAULT_CONFIG(i2s_port_t(1), I2S_ROLE_MASTER); + spkr_chan_config.auto_clear = true; // Auto clear the legacy data in the DMA buffer + + ESP_ERROR_CHECK(i2s_new_channel(&mic_chan_config, NULL, &rx_handle_)); + ESP_ERROR_CHECK(i2s_new_channel(&spkr_chan_config, &tx_handle_, NULL)); + + i2s_pdm_rx_config_t mic_config = { + .clk_cfg = I2S_PDM_RX_CLK_DEFAULT_CONFIG(static_cast(input_sample_rate_)), + /* The data bit-width of PDM mode is fixed to 16 */ + .slot_cfg = I2S_PDM_RX_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_STEREO), + .gpio_cfg = { + .clk = mic_ws, + .din = mic_data, + .invert_flags = { + .clk_inv = false, + }, + }, + }; + + i2s_std_config_t spkr_config = { + .clk_cfg ={ + .sample_rate_hz = static_cast(11025), + .clk_src = I2S_CLK_SRC_DEFAULT, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + #ifdef I2S_HW_VERSION_2 + .ext_clk_freq_hz = 0, + #endif + }, + .slot_cfg = I2S_STD_PHILIPS_SLOT_DEFAULT_CONFIG(I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_STEREO), + .gpio_cfg ={ + .mclk = I2S_GPIO_UNUSED, + .bclk = spkr_bclk, + .ws = spkr_lrclk, + .dout = spkr_data, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_pdm_rx_mode(rx_handle_, &mic_config)); + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &spkr_config)); + ESP_LOGI(TAG, "Voice hardware created"); +} + +void Tdisplays3promvsrloraAudioCodec::SetOutputVolume(int volume) { + volume_ = volume; + AudioCodec::SetOutputVolume(volume); +} + +void Tdisplays3promvsrloraAudioCodec::EnableInput(bool enable) { + gpio_set_level(AUDIO_MIC_ENABLE, !enable); + AudioCodec::EnableInput(enable); +} + +void Tdisplays3promvsrloraAudioCodec::EnableOutput(bool enable) { + gpio_set_level(AUDIO_SPKR_ENABLE, enable); + AudioCodec::EnableOutput(enable); +} + +int Tdisplays3promvsrloraAudioCodec::Read(int16_t *dest, int samples){ + if (input_enabled_){ + size_t bytes_read; + i2s_channel_read(rx_handle_, dest, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + + // ESP_LOGI(TAG, "Left: %d\n", dest[0]); + // ESP_LOGI(TAG,"Right: %d\n", dest[1]); + } + return samples; +} + +int Tdisplays3promvsrloraAudioCodec::Write(const int16_t *data, int samples){ + if (output_enabled_){ + size_t bytes_read; + auto output_data = (int16_t *)malloc(samples * sizeof(int16_t)); + for (size_t i = 0; i < samples; i++){ + output_data[i] = (float)data[i] * (float)(volume_ / 100.0); + } + i2s_channel_write(tx_handle_, output_data, samples * sizeof(int16_t), &bytes_read, portMAX_DELAY); + free(output_data); + } + return samples; +} diff --git a/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.h b/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.h new file mode 100644 index 0000000..6612b96 --- /dev/null +++ b/main/boards/lilygo-t-display-s3-pro-mvsrlora/tdisplays3promvsrlora_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _TDISPLAYS3PROMVSRLORA_AUDIO_CODEC_H +#define _TDISPLAYS3PROMVSRLORA_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class Tdisplays3promvsrloraAudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t *data_if_ = nullptr; + const audio_codec_ctrl_if_t *out_ctrl_if_ = nullptr; + const audio_codec_if_t *out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t *in_ctrl_if_ = nullptr; + const audio_codec_if_t *in_codec_if_ = nullptr; + const audio_codec_gpio_if_t *gpio_if_ = nullptr; + + uint32_t volume_ = 70; + + void CreateVoiceHardware(gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data,gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data); + + virtual int Read(int16_t *dest, int samples) override; + virtual int Write(const int16_t *data, int samples) override; + +public: +Tdisplays3promvsrloraAudioCodec(int input_sample_rate, int output_sample_rate, + gpio_num_t mic_bclk, gpio_num_t mic_ws, gpio_num_t mic_data, + gpio_num_t spkr_bclk, gpio_num_t spkr_lrclk, gpio_num_t spkr_data, + bool input_reference); + virtual ~Tdisplays3promvsrloraAudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/m5stack-core-s3/README.md b/main/boards/m5stack-core-s3/README.md new file mode 100644 index 0000000..d7aa9b8 --- /dev/null +++ b/main/boards/m5stack-core-s3/README.md @@ -0,0 +1,22 @@ +# 使用说明 + + +**编译** + +```bash +python ./scripts/release.py m5stack-core-s3 +``` + +如需手动编译,请参考 `m5stack-core-s3/config.json` 修改 menuconfig 对应选项。 + +**烧录** + +```bash +idf.py flash +``` + +> [!NOTE] +> 进入下载模式:长按复位按键(约3秒),直至内部指示灯亮绿色,松开按键。 + + + diff --git a/main/boards/m5stack-core-s3/config.h b/main/boards/m5stack-core-s3/config.h new file mode 100644 index 0000000..e003782 --- /dev/null +++ b/main/boards/m5stack-core-s3/config.h @@ -0,0 +1,66 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// M5Stack CoreS3 Board configuration + +#include + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_0 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_33 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_34 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_13 + +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_12 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_11 +#define AUDIO_CODEC_AW88298_ADDR AW88298_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA_PIN GPIO_NUM_NC +#define DISPLAY_SCL_PIN GPIO_NUM_NC +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + + +/* Camera pins */ +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_XCLK GPIO_NUM_NC // 像素时钟 (固定由 20MHz 外部晶振输入) +#define CAMERA_PIN_SIOD GPIO_NUM_NC // 串行时钟 Using existing I2C port +#define CAMERA_PIN_SIOC GPIO_NUM_NC // 串行时钟 Using existing I2C port +#define CAMERA_PIN_D0 GPIO_NUM_39 +#define CAMERA_PIN_D1 GPIO_NUM_40 +#define CAMERA_PIN_D2 GPIO_NUM_41 +#define CAMERA_PIN_D3 GPIO_NUM_42 +#define CAMERA_PIN_D4 GPIO_NUM_15 +#define CAMERA_PIN_D5 GPIO_NUM_16 +#define CAMERA_PIN_D6 GPIO_NUM_48 +#define CAMERA_PIN_D7 GPIO_NUM_47 +#define CAMERA_PIN_VSYNC GPIO_NUM_46 +#define CAMERA_PIN_HREF GPIO_NUM_38 +#define CAMERA_PIN_PCLK GPIO_NUM_45 + +#define XCLK_FREQ_HZ 20000000 + + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/m5stack-core-s3/config.json b/main/boards/m5stack-core-s3/config.json new file mode 100644 index 0000000..84ba5b7 --- /dev/null +++ b/main/boards/m5stack-core-s3/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "m5stack-core-s3", + "sdkconfig_append": [ + "CONFIG_SPIRAM_MODE_QUAD=y", + "CONFIG_CAMERA_GC0308=y", + "CONFIG_CAMERA_GC0308_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_GC0308_DVP_YUV422_320X240_20FPS=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/m5stack-core-s3/cores3_audio_codec.cc b/main/boards/m5stack-core-s3/cores3_audio_codec.cc new file mode 100644 index 0000000..2596391 --- /dev/null +++ b/main/boards/m5stack-core-s3/cores3_audio_codec.cc @@ -0,0 +1,244 @@ +#include "cores3_audio_codec.h" + +#include +#include +#include + +#define TAG "CoreS3AudioCodec" + +CoreS3AudioCodec::CoreS3AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + uint8_t aw88298_addr, uint8_t es7210_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 30; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Audio Output(Speaker) + audio_codec_i2c_cfg_t i2c_cfg = { + .port = (i2c_port_t)1, + .addr = aw88298_addr, + .bus_handle = i2c_master_handle, + }; + out_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(out_ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + aw88298_codec_cfg_t aw88298_cfg = {}; + aw88298_cfg.ctrl_if = out_ctrl_if_; + aw88298_cfg.gpio_if = gpio_if_; + aw88298_cfg.reset_pin = GPIO_NUM_NC; + aw88298_cfg.hw_gain.pa_voltage = 5.0; + aw88298_cfg.hw_gain.codec_dac_voltage = 3.3; + aw88298_cfg.hw_gain.pa_gain = 1; + out_codec_if_ = aw88298_codec_new(&aw88298_cfg); + assert(out_codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = out_codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + + // Audio Input(Microphone) + i2c_cfg.addr = es7210_addr; + in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7210_codec_cfg_t es7210_cfg = {}; + es7210_cfg.ctrl_if = in_ctrl_if_; + es7210_cfg.mic_selected = ES7210_SEL_MIC1 | ES7210_SEL_MIC2 | ES7210_SEL_MIC3; + in_codec_if_ = es7210_codec_new(&es7210_cfg); + assert(in_codec_if_ != NULL); + + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + dev_cfg.codec_if = in_codec_if_; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + + ESP_LOGI(TAG, "CoreS3AudioCodec initialized"); +} + +CoreS3AudioCodec::~CoreS3AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void CoreS3AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + ESP_LOGI(TAG, "Audio IOs: mclk: %d, bclk: %d, ws: %d, dout: %d, din: %d", mclk, bclk, ws, dout, din); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + i2s_tdm_config_t tdm_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + .bclk_div = 8, + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = i2s_tdm_slot_mask_t(I2S_TDM_SLOT0 | I2S_TDM_SLOT1 | I2S_TDM_SLOT2 | I2S_TDM_SLOT3), + .ws_width = I2S_TDM_AUTO_WS_WIDTH, + .ws_pol = false, + .bit_shift = true, + .left_align = false, + .big_endian = false, + .bit_order_lsb = false, + .skip_mask = false, + .total_slot = I2S_TDM_AUTO_SLOT_NUM + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = I2S_GPIO_UNUSED, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_tdm_mode(rx_handle_, &tdm_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void CoreS3AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void CoreS3AudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 2, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + if (input_reference_) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_channel_gain(input_dev_, ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), input_gain_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void CoreS3AudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + } + AudioCodec::EnableOutput(enable); +} + +int CoreS3AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int CoreS3AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} diff --git a/main/boards/m5stack-core-s3/cores3_audio_codec.h b/main/boards/m5stack-core-s3/cores3_audio_codec.h new file mode 100644 index 0000000..4b034b4 --- /dev/null +++ b/main/boards/m5stack-core-s3/cores3_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _BOX_AUDIO_CODEC_H +#define _BOX_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class CoreS3AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + CoreS3AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + uint8_t aw88298_addr, uint8_t es7210_addr, bool input_reference); + virtual ~CoreS3AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _BOX_AUDIO_CODEC_H diff --git a/main/boards/m5stack-core-s3/m5stack_core_s3.cc b/main/boards/m5stack-core-s3/m5stack_core_s3.cc new file mode 100644 index 0000000..9b45f07 --- /dev/null +++ b/main/boards/m5stack-core-s3/m5stack_core_s3.cc @@ -0,0 +1,397 @@ +#include "wifi_board.h" +#include "cores3_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "config.h" +#include "power_save_timer.h" +#include "i2c_device.h" +#include "axp2101.h" + +#include +#include +#include +#include +#include +#include +#include +#include "esp32_camera.h" + +#define TAG "M5StackCoreS3Board" + +class Pmic : public Axp2101 { +public: + // Power Init + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + uint8_t data = ReadReg(0x90); + data |= 0b10110100; + WriteReg(0x90, data); + WriteReg(0x99, (0b11110 - 5)); + WriteReg(0x97, (0b11110 - 2)); + WriteReg(0x69, 0b00110101); + WriteReg(0x30, 0b111111); + WriteReg(0x90, 0xBF); + WriteReg(0x94, 33 - 5); + WriteReg(0x95, 33 - 5); + } + + void SetBrightness(uint8_t brightness) { + brightness = ((brightness + 641) >> 5); + WriteReg(0x99, brightness); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(Pmic *pmic) : pmic_(pmic) {} + + void SetBrightnessImpl(uint8_t brightness) override { + pmic_->SetBrightness(target_brightness_); + brightness_ = target_brightness_; + } + +private: + Pmic *pmic_; +}; + +class Aw9523 : public I2cDevice { +public: + // Exanpd IO Init + Aw9523(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(0x02, 0b00000111); // P0 + WriteReg(0x03, 0b10001111); // P1 + WriteReg(0x04, 0b00011000); // CONFIG_P0 + WriteReg(0x05, 0b00001100); // CONFIG_P1 + WriteReg(0x11, 0b00010000); // GCR P0 port is Push-Pull mode. + WriteReg(0x12, 0b11111111); // LEDMODE_P0 + WriteReg(0x13, 0b11111111); // LEDMODE_P1 + } + + void ResetAw88298() { + ESP_LOGI(TAG, "Reset AW88298"); + WriteReg(0x02, 0b00000011); + vTaskDelay(pdMS_TO_TICKS(10)); + WriteReg(0x02, 0b00000111); + vTaskDelay(pdMS_TO_TICKS(50)); + } + + void ResetIli9342() { + ESP_LOGI(TAG, "Reset IlI9342"); + WriteReg(0x03, 0b10000001); + vTaskDelay(pdMS_TO_TICKS(20)); + WriteReg(0x03, 0b10000011); + vTaskDelay(pdMS_TO_TICKS(10)); + } +}; + +class Ft6336 : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + Ft6336(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA3); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Ft6336() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + inline const TouchPoint_t& GetTouchPoint() { + return tp_; + } + +private: + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class M5StackCoreS3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_; + Aw9523* aw9523_; + Ft6336* ft6336_; + LcdDisplay* display_; + Esp32Camera* camera_; + esp_timer_handle_t touchpad_timer_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeAw9523() { + ESP_LOGI(TAG, "Init AW9523"); + aw9523_ = new Aw9523(i2c_bus_, 0x58); + vTaskDelay(pdMS_TO_TICKS(50)); + } + + void PollTouchpad() { + static bool was_touched = false; + static int64_t touch_start_time = 0; + const int64_t TOUCH_THRESHOLD_MS = 500; // 触摸时长阈值,超过500ms视为长按 + + ft6336_->UpdateTouchPoint(); + auto& touch_point = ft6336_->GetTouchPoint(); + + // 检测触摸开始 + if (touch_point.num > 0 && !was_touched) { + was_touched = true; + touch_start_time = esp_timer_get_time() / 1000; // 转换为毫秒 + } + // 检测触摸释放 + else if (touch_point.num == 0 && was_touched) { + was_touched = false; + int64_t touch_duration = (esp_timer_get_time() / 1000) - touch_start_time; + + // 只有短触才触发 + if (touch_duration < TOUCH_THRESHOLD_MS) { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + } + } + + void InitializeFt6336TouchPad() { + ESP_LOGI(TAG, "Init FT6336"); + ft6336_ = new Ft6336(i2c_bus_, 0x38); + + // 创建定时器,20ms 间隔 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + M5StackCoreS3Board* board = (M5StackCoreS3Board*)arg; + board->PollTouchpad(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "touchpad_timer", + .skip_unhandled_events = true, + }; + + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &touchpad_timer_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(touchpad_timer_, 20 * 1000)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = GPIO_NUM_37; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = GPIO_NUM_36; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeIli9342Display() { + ESP_LOGI(TAG, "Init IlI9342"); + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = GPIO_NUM_3; + io_config.dc_gpio_num = GPIO_NUM_35; + io_config.spi_mode = 2; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + aw9523_->ResetIli9342(); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 100000, + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = XCLK_FREQ_HZ, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + camera_->SetHMirror(false); + } + +public: + M5StackCoreS3Board() { + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeAxp2101(); + InitializeAw9523(); + I2cDetect(); + InitializeSpi(); + InitializeIli9342Display(); + InitializeCamera(); + InitializeFt6336TouchPad(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static CoreS3AudioCodec audio_codec(i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_AW88298_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual Backlight *GetBacklight() override { + static CustomBacklight backlight(pmic_); + return &backlight; + } +}; + +DECLARE_BOARD(M5StackCoreS3Board); diff --git a/main/boards/m5stack-tab5/README.md b/main/boards/m5stack-tab5/README.md new file mode 100644 index 0000000..edbe24b --- /dev/null +++ b/main/boards/m5stack-tab5/README.md @@ -0,0 +1,57 @@ +# 使用说明 + +* [M5Stack Tab5 docs](https://docs.m5stack.com/zh_CN/core/Tab5) + +## 快速体验 + +到 [M5Burner](https://docs.m5stack.com/zh_CN/uiflow/m5burner/intro) 选择 Tab5 搜索小智下载固件 + +## 基础使用 + +* idf version: v6.0-dev + +1. 调整 idf_component.yml + +将 +```yaml + espressif/esp_video: + version: ==1.3.1 # for compatibility. update version may need to modify this project code. + rules: + - if: target not in [esp32] +``` +修改为 +```yaml + espressif/esp_video: + version: '==0.7.0' + rules: + - if: target not in [esp32] + espressif/esp_ipa: '==0.1.0' +``` + +2. 使用 release.py 编译 + +```shell +python ./scripts/release.py m5stack-tab5 +``` + +如需手动编译,请参考 `m5stack-tab5/config.json` 修改 menuconfig 对应选项。 + +3. 编译烧录程序 + +```shell +idf.py flash monitor +``` + +> [!NOTE] +> 进入下载模式:长按复位按键(约 2 秒),直至内部绿色 LED 指示灯开始快速闪烁,松开按键。 + + +## log + +@2025/05/17 测试问题 + +1. listening... 需要等几秒才能获取语音输入??? +2. 亮度调节不对 +3. 音量调节不对 + +## TODO diff --git a/main/boards/m5stack-tab5/config.h b/main/boards/m5stack-tab5/config.h new file mode 100644 index 0000000..91b6abf --- /dev/null +++ b/main/boards/m5stack-tab5/config.h @@ -0,0 +1,325 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +/* ---------------------------------------------------------------- */ +// Audio CODEC ES7210 + ES8311 +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_30 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_29 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_27 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_28 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_26 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC // PI4IOE 控制 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_31 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_32 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +/* ---------------------------------------------------------------- */ +// 摄像头相关参数配置 +#define CAMERA_SCL GPIO_NUM_32 +#define CAMERA_SDA GPIO_NUM_31 +#define CAMERA_MCLK GPIO_NUM_36 + +/* ---------------------------------------------------------------- */ +// 显示屏相关参数配置 +#define DISPLAY_WIDTH 720 +#define DISPLAY_HEIGHT 1280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_22 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#define TOUCH_INT_GPIO GPIO_NUM_23 // 触摸中断 + +const ili9881c_lcd_init_cmd_t tab5_lcd_ili9881c_specific_init_code_default[] = { + // {cmd, { data }, data_size, delay} + /**** CMD_Page 1 ****/ + {0xFF, (uint8_t[]){0x98, 0x81, 0x01}, 3, 0}, + {0xB7, (uint8_t[]){0x03}, 1, 0}, // set 2 lane + /**** CMD_Page 3 ****/ + {0xFF, (uint8_t[]){0x98, 0x81, 0x03}, 3, 0}, + {0x01, (uint8_t[]){0x00}, 1, 0}, + {0x02, (uint8_t[]){0x00}, 1, 0}, + {0x03, (uint8_t[]){0x73}, 1, 0}, + {0x04, (uint8_t[]){0x00}, 1, 0}, + {0x05, (uint8_t[]){0x00}, 1, 0}, + {0x06, (uint8_t[]){0x08}, 1, 0}, + {0x07, (uint8_t[]){0x00}, 1, 0}, + {0x08, (uint8_t[]){0x00}, 1, 0}, + {0x09, (uint8_t[]){0x1B}, 1, 0}, + {0x0a, (uint8_t[]){0x01}, 1, 0}, + {0x0b, (uint8_t[]){0x01}, 1, 0}, + {0x0c, (uint8_t[]){0x0D}, 1, 0}, + {0x0d, (uint8_t[]){0x01}, 1, 0}, + {0x0e, (uint8_t[]){0x01}, 1, 0}, + {0x0f, (uint8_t[]){0x26}, 1, 0}, + {0x10, (uint8_t[]){0x26}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 1, 0}, + {0x12, (uint8_t[]){0x00}, 1, 0}, + {0x13, (uint8_t[]){0x02}, 1, 0}, + {0x14, (uint8_t[]){0x00}, 1, 0}, + {0x15, (uint8_t[]){0x00}, 1, 0}, + {0x16, (uint8_t[]){0x00}, 1, 0}, + {0x17, (uint8_t[]){0x00}, 1, 0}, + {0x18, (uint8_t[]){0x00}, 1, 0}, + {0x19, (uint8_t[]){0x00}, 1, 0}, + {0x1a, (uint8_t[]){0x00}, 1, 0}, + {0x1b, (uint8_t[]){0x00}, 1, 0}, + {0x1c, (uint8_t[]){0x00}, 1, 0}, + {0x1d, (uint8_t[]){0x00}, 1, 0}, + {0x1e, (uint8_t[]){0x40}, 1, 0}, + {0x1f, (uint8_t[]){0x00}, 1, 0}, + {0x20, (uint8_t[]){0x06}, 1, 0}, + {0x21, (uint8_t[]){0x01}, 1, 0}, + {0x22, (uint8_t[]){0x00}, 1, 0}, + {0x23, (uint8_t[]){0x00}, 1, 0}, + {0x24, (uint8_t[]){0x00}, 1, 0}, + {0x25, (uint8_t[]){0x00}, 1, 0}, + {0x26, (uint8_t[]){0x00}, 1, 0}, + {0x27, (uint8_t[]){0x00}, 1, 0}, + {0x28, (uint8_t[]){0x33}, 1, 0}, + {0x29, (uint8_t[]){0x03}, 1, 0}, + {0x2a, (uint8_t[]){0x00}, 1, 0}, + {0x2b, (uint8_t[]){0x00}, 1, 0}, + {0x2c, (uint8_t[]){0x00}, 1, 0}, + {0x2d, (uint8_t[]){0x00}, 1, 0}, + {0x2e, (uint8_t[]){0x00}, 1, 0}, + {0x2f, (uint8_t[]){0x00}, 1, 0}, + {0x30, (uint8_t[]){0x00}, 1, 0}, + {0x31, (uint8_t[]){0x00}, 1, 0}, + {0x32, (uint8_t[]){0x00}, 1, 0}, + {0x33, (uint8_t[]){0x00}, 1, 0}, + {0x34, (uint8_t[]){0x00}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 1, 0}, + {0x36, (uint8_t[]){0x00}, 1, 0}, + {0x37, (uint8_t[]){0x00}, 1, 0}, + {0x38, (uint8_t[]){0x00}, 1, 0}, + {0x39, (uint8_t[]){0x00}, 1, 0}, + {0x3a, (uint8_t[]){0x00}, 1, 0}, + {0x3b, (uint8_t[]){0x00}, 1, 0}, + {0x3c, (uint8_t[]){0x00}, 1, 0}, + {0x3d, (uint8_t[]){0x00}, 1, 0}, + {0x3e, (uint8_t[]){0x00}, 1, 0}, + {0x3f, (uint8_t[]){0x00}, 1, 0}, + {0x40, (uint8_t[]){0x00}, 1, 0}, + {0x41, (uint8_t[]){0x00}, 1, 0}, + {0x42, (uint8_t[]){0x00}, 1, 0}, + {0x43, (uint8_t[]){0x00}, 1, 0}, + {0x44, (uint8_t[]){0x00}, 1, 0}, + + {0x50, (uint8_t[]){0x01}, 1, 0}, + {0x51, (uint8_t[]){0x23}, 1, 0}, + {0x52, (uint8_t[]){0x45}, 1, 0}, + {0x53, (uint8_t[]){0x67}, 1, 0}, + {0x54, (uint8_t[]){0x89}, 1, 0}, + {0x55, (uint8_t[]){0xab}, 1, 0}, + {0x56, (uint8_t[]){0x01}, 1, 0}, + {0x57, (uint8_t[]){0x23}, 1, 0}, + {0x58, (uint8_t[]){0x45}, 1, 0}, + {0x59, (uint8_t[]){0x67}, 1, 0}, + {0x5a, (uint8_t[]){0x89}, 1, 0}, + {0x5b, (uint8_t[]){0xab}, 1, 0}, + {0x5c, (uint8_t[]){0xcd}, 1, 0}, + {0x5d, (uint8_t[]){0xef}, 1, 0}, + + {0x5e, (uint8_t[]){0x11}, 1, 0}, + {0x5f, (uint8_t[]){0x02}, 1, 0}, + {0x60, (uint8_t[]){0x00}, 1, 0}, + {0x61, (uint8_t[]){0x07}, 1, 0}, + {0x62, (uint8_t[]){0x06}, 1, 0}, + {0x63, (uint8_t[]){0x0E}, 1, 0}, + {0x64, (uint8_t[]){0x0F}, 1, 0}, + {0x65, (uint8_t[]){0x0C}, 1, 0}, + {0x66, (uint8_t[]){0x0D}, 1, 0}, + {0x67, (uint8_t[]){0x02}, 1, 0}, + {0x68, (uint8_t[]){0x02}, 1, 0}, + {0x69, (uint8_t[]){0x02}, 1, 0}, + {0x6a, (uint8_t[]){0x02}, 1, 0}, + {0x6b, (uint8_t[]){0x02}, 1, 0}, + {0x6c, (uint8_t[]){0x02}, 1, 0}, + {0x6d, (uint8_t[]){0x02}, 1, 0}, + {0x6e, (uint8_t[]){0x02}, 1, 0}, + {0x6f, (uint8_t[]){0x02}, 1, 0}, + {0x70, (uint8_t[]){0x02}, 1, 0}, + {0x71, (uint8_t[]){0x02}, 1, 0}, + {0x72, (uint8_t[]){0x02}, 1, 0}, + {0x73, (uint8_t[]){0x05}, 1, 0}, + {0x74, (uint8_t[]){0x01}, 1, 0}, + {0x75, (uint8_t[]){0x02}, 1, 0}, + {0x76, (uint8_t[]){0x00}, 1, 0}, + {0x77, (uint8_t[]){0x07}, 1, 0}, + {0x78, (uint8_t[]){0x06}, 1, 0}, + {0x79, (uint8_t[]){0x0E}, 1, 0}, + {0x7a, (uint8_t[]){0x0F}, 1, 0}, + {0x7b, (uint8_t[]){0x0C}, 1, 0}, + {0x7c, (uint8_t[]){0x0D}, 1, 0}, + {0x7d, (uint8_t[]){0x02}, 1, 0}, + {0x7e, (uint8_t[]){0x02}, 1, 0}, + {0x7f, (uint8_t[]){0x02}, 1, 0}, + {0x80, (uint8_t[]){0x02}, 1, 0}, + {0x81, (uint8_t[]){0x02}, 1, 0}, + {0x82, (uint8_t[]){0x02}, 1, 0}, + {0x83, (uint8_t[]){0x02}, 1, 0}, + {0x84, (uint8_t[]){0x02}, 1, 0}, + {0x85, (uint8_t[]){0x02}, 1, 0}, + {0x86, (uint8_t[]){0x02}, 1, 0}, + {0x87, (uint8_t[]){0x02}, 1, 0}, + {0x88, (uint8_t[]){0x02}, 1, 0}, + {0x89, (uint8_t[]){0x05}, 1, 0}, + {0x8A, (uint8_t[]){0x01}, 1, 0}, + + /**** CMD_Page 4 ****/ + {0xFF, (uint8_t[]){0x98, 0x81, 0x04}, 3, 0}, + {0x38, (uint8_t[]){0x01}, 1, 0}, + {0x39, (uint8_t[]){0x00}, 1, 0}, + {0x6C, (uint8_t[]){0x15}, 1, 0}, + {0x6E, (uint8_t[]){0x1A}, 1, 0}, + {0x6F, (uint8_t[]){0x25}, 1, 0}, + {0x3A, (uint8_t[]){0xA4}, 1, 0}, + {0x8D, (uint8_t[]){0x20}, 1, 0}, + {0x87, (uint8_t[]){0xBA}, 1, 0}, + {0x3B, (uint8_t[]){0x98}, 1, 0}, + + /**** CMD_Page 1 ****/ + {0xFF, (uint8_t[]){0x98, 0x81, 0x01}, 3, 0}, + {0x22, (uint8_t[]){0x0A}, 1, 0}, + {0x31, (uint8_t[]){0x00}, 1, 0}, + {0x50, (uint8_t[]){0x6B}, 1, 0}, + {0x51, (uint8_t[]){0x66}, 1, 0}, + {0x53, (uint8_t[]){0x73}, 1, 0}, + {0x55, (uint8_t[]){0x8B}, 1, 0}, + {0x60, (uint8_t[]){0x1B}, 1, 0}, + {0x61, (uint8_t[]){0x01}, 1, 0}, + {0x62, (uint8_t[]){0x0C}, 1, 0}, + {0x63, (uint8_t[]){0x00}, 1, 0}, + + // Gamma P + {0xA0, (uint8_t[]){0x00}, 1, 0}, + {0xA1, (uint8_t[]){0x15}, 1, 0}, + {0xA2, (uint8_t[]){0x1F}, 1, 0}, + {0xA3, (uint8_t[]){0x13}, 1, 0}, + {0xA4, (uint8_t[]){0x11}, 1, 0}, + {0xA5, (uint8_t[]){0x21}, 1, 0}, + {0xA6, (uint8_t[]){0x17}, 1, 0}, + {0xA7, (uint8_t[]){0x1B}, 1, 0}, + {0xA8, (uint8_t[]){0x6B}, 1, 0}, + {0xA9, (uint8_t[]){0x1E}, 1, 0}, + {0xAA, (uint8_t[]){0x2B}, 1, 0}, + {0xAB, (uint8_t[]){0x5D}, 1, 0}, + {0xAC, (uint8_t[]){0x19}, 1, 0}, + {0xAD, (uint8_t[]){0x14}, 1, 0}, + {0xAE, (uint8_t[]){0x4B}, 1, 0}, + {0xAF, (uint8_t[]){0x1D}, 1, 0}, + {0xB0, (uint8_t[]){0x27}, 1, 0}, + {0xB1, (uint8_t[]){0x49}, 1, 0}, + {0xB2, (uint8_t[]){0x5D}, 1, 0}, + {0xB3, (uint8_t[]){0x39}, 1, 0}, + + // Gamma N + {0xC0, (uint8_t[]){0x00}, 1, 0}, + {0xC1, (uint8_t[]){0x01}, 1, 0}, + {0xC2, (uint8_t[]){0x0C}, 1, 0}, + {0xC3, (uint8_t[]){0x11}, 1, 0}, + {0xC4, (uint8_t[]){0x15}, 1, 0}, + {0xC5, (uint8_t[]){0x28}, 1, 0}, + {0xC6, (uint8_t[]){0x1B}, 1, 0}, + {0xC7, (uint8_t[]){0x1C}, 1, 0}, + {0xC8, (uint8_t[]){0x62}, 1, 0}, + {0xC9, (uint8_t[]){0x1C}, 1, 0}, + {0xCA, (uint8_t[]){0x29}, 1, 0}, + {0xCB, (uint8_t[]){0x60}, 1, 0}, + {0xCC, (uint8_t[]){0x16}, 1, 0}, + {0xCD, (uint8_t[]){0x17}, 1, 0}, + {0xCE, (uint8_t[]){0x4A}, 1, 0}, + {0xCF, (uint8_t[]){0x23}, 1, 0}, + {0xD0, (uint8_t[]){0x24}, 1, 0}, + {0xD1, (uint8_t[]){0x4F}, 1, 0}, + {0xD2, (uint8_t[]){0x5F}, 1, 0}, + {0xD3, (uint8_t[]){0x39}, 1, 0}, + + /**** CMD_Page 0 ****/ + {0xFF, (uint8_t[]){0x98, 0x81, 0x00}, 3, 0}, + {0x35, (uint8_t[]){0x00}, 0, 0}, + // {0x11, (uint8_t []){0x00}, 0}, + {0xFE, (uint8_t[]){0x00}, 0, 0}, + {0x29, (uint8_t[]){0x00}, 0, 0}, + //============ Gamma END=========== +}; + +// ST7123 vendor specific initialization commands +const st7123_lcd_init_cmd_t st7123_vendor_specific_init_default[] = { + {0x60, (uint8_t[]){0x71, 0x23, 0xa2}, 3, 0}, + {0x60, (uint8_t[]){0x71, 0x23, 0xa3}, 3, 0}, + {0x60, (uint8_t[]){0x71, 0x23, 0xa4}, 3, 0}, + {0xA4, (uint8_t[]){0x31}, 1, 0}, + {0xD7, (uint8_t[]){0x10, 0x0A, 0x10, 0x2A, 0x80, 0x80}, 6, 0}, + {0x90, (uint8_t[]){0x71, 0x23, 0x5A, 0x20, 0x24, 0x09, 0x09}, 7, 0}, + {0xA3, (uint8_t[]){0x80, 0x01, 0x88, 0x30, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x46, 0x00, 0x00, + 0x1E, 0x5C, 0x1E, 0x80, 0x00, 0x4F, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x00, 0x1E, 0x5C, 0x1E, 0x80, 0x00, 0x6F, 0x58, 0x00, 0x00, 0x00, 0xFF}, + 40, 0}, + {0xA6, (uint8_t[]){0x03, 0x00, 0x24, 0x55, 0x36, 0x00, 0x39, 0x00, 0x6E, 0x6E, 0x91, 0xFF, 0x00, 0x24, + 0x55, 0x38, 0x00, 0x37, 0x00, 0x6E, 0x6E, 0x91, 0xFF, 0x00, 0x24, 0x11, 0x00, 0x00, + 0x00, 0x00, 0x6E, 0x6E, 0x91, 0xFF, 0x00, 0xEC, 0x11, 0x00, 0x03, 0x00, 0x03, 0x6E, + 0x6E, 0xFF, 0xFF, 0x00, 0x08, 0x80, 0x08, 0x80, 0x06, 0x00, 0x00, 0x00, 0x00}, + 55, 0}, + {0xA7, (uint8_t[]){0x19, 0x19, 0x80, 0x64, 0x40, 0x07, 0x16, 0x40, 0x00, 0x44, 0x03, 0x6E, 0x6E, 0x91, 0xFF, + 0x08, 0x80, 0x64, 0x40, 0x25, 0x34, 0x40, 0x00, 0x02, 0x01, 0x6E, 0x6E, 0x91, 0xFF, 0x08, + 0x80, 0x64, 0x40, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x6E, 0x6E, 0x91, 0xFF, 0x08, 0x80, + 0x64, 0x40, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x6E, 0x6E, 0x84, 0xFF, 0x08, 0x80, 0x44}, + 60, 0}, + {0xAC, (uint8_t[]){0x03, 0x19, 0x19, 0x18, 0x18, 0x06, 0x13, 0x13, 0x11, 0x11, 0x08, 0x08, 0x0A, 0x0A, 0x1C, + 0x1C, 0x07, 0x07, 0x00, 0x00, 0x02, 0x02, 0x01, 0x19, 0x19, 0x18, 0x18, 0x06, 0x12, 0x12, + 0x10, 0x10, 0x09, 0x09, 0x0B, 0x0B, 0x1C, 0x1C, 0x07, 0x07, 0x03, 0x03, 0x01, 0x01}, + 44, 0}, + {0xAD, (uint8_t[]){0xF0, 0x00, 0x46, 0x00, 0x03, 0x50, 0x50, 0xFF, 0xFF, 0xF0, 0x40, 0x06, 0x01, + 0x07, 0x42, 0x42, 0xFF, 0xFF, 0x01, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF}, + 25, 0}, + {0xAE, (uint8_t[]){0xFE, 0x3F, 0x3F, 0xFE, 0x3F, 0x3F, 0x00}, 7, 0}, + {0xB2, + (uint8_t[]){0x15, 0x19, 0x05, 0x23, 0x49, 0xAF, 0x03, 0x2E, 0x5C, 0xD2, 0xFF, 0x10, 0x20, 0xFD, 0x20, 0xC0, 0x00}, + 17, 0}, + {0xE8, (uint8_t[]){0x20, 0x6F, 0x04, 0x97, 0x97, 0x3E, 0x04, 0xDC, 0xDC, 0x3E, 0x06, 0xFA, 0x26, 0x3E}, 15, 0}, + {0x75, (uint8_t[]){0x03, 0x04}, 2, 0}, + {0xE7, (uint8_t[]){0x3B, 0x00, 0x00, 0x7C, 0xA1, 0x8C, 0x20, 0x1A, 0xF0, 0xB1, 0x50, 0x00, + 0x50, 0xB1, 0x50, 0xB1, 0x50, 0xD8, 0x00, 0x55, 0x00, 0xB1, 0x00, 0x45, + 0xC9, 0x6A, 0xFF, 0x5A, 0xD8, 0x18, 0x88, 0x15, 0xB1, 0x01, 0x01, 0x77}, + 36, 0}, + {0xEA, (uint8_t[]){0x13, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x2C}, 8, 0}, + {0xB0, (uint8_t[]){0x22, 0x43, 0x11, 0x61, 0x25, 0x43, 0x43}, 7, 0}, + {0xb7, (uint8_t[]){0x00, 0x00, 0x73, 0x73}, 4, 0}, + {0xBF, (uint8_t[]){0xA6, 0xAA}, 2, 0}, + {0xA9, (uint8_t[]){0x00, 0x00, 0x73, 0xFF, 0x00, 0x00, 0x03, 0x00, 0x00, 0x03}, 10, 0}, + {0xC8, (uint8_t[]){0x00, 0x00, 0x10, 0x1F, 0x36, 0x00, 0x5D, 0x04, 0x9D, 0x05, 0x10, 0xF2, 0x06, + 0x60, 0x03, 0x11, 0xAD, 0x00, 0xEF, 0x01, 0x22, 0x2E, 0x0E, 0x74, 0x08, 0x32, + 0xDC, 0x09, 0x33, 0x0F, 0xF3, 0x77, 0x0D, 0xB0, 0xDC, 0x03, 0xFF}, + 37, 0}, + {0xC9, (uint8_t[]){0x00, 0x00, 0x10, 0x1F, 0x36, 0x00, 0x5D, 0x04, 0x9D, 0x05, 0x10, 0xF2, 0x06, + 0x60, 0x03, 0x11, 0xAD, 0x00, 0xEF, 0x01, 0x22, 0x2E, 0x0E, 0x74, 0x08, 0x32, + 0xDC, 0x09, 0x33, 0x0F, 0xF3, 0x77, 0x0D, 0xB0, 0xDC, 0x03, 0xFF}, + 37, 0}, + {0x36, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 1, 100}, + {0x29, (uint8_t[]){0x00}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 1, 100}, +}; + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/m5stack-tab5/config.json b/main/boards/m5stack-tab5/config.json new file mode 100644 index 0000000..c229ea0 --- /dev/null +++ b/main/boards/m5stack-tab5/config.json @@ -0,0 +1,19 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "m5stack-tab5", + "sdkconfig_append": [ + "CONFIG_BOARD_TYPE_M5STACK_CORE_TAB5=y", + "CONFIG_CAMERA_SC202CS=y", + "CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE=y", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_CMD_SLOT_1=13", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_CLK_SLOT_1=12", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D0_SLOT_1=11", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D1_4BIT_BUS_SLOT_1=10", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D2_4BIT_BUS_SLOT_1=9", + "CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D3_4BIT_BUS_SLOT_1=8" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/m5stack-tab5/esp_lcd_st7123.c b/main/boards/m5stack-tab5/esp_lcd_st7123.c new file mode 100644 index 0000000..b68b1d3 --- /dev/null +++ b/main/boards/m5stack-tab5/esp_lcd_st7123.c @@ -0,0 +1,381 @@ +/* + * SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "soc/soc_caps.h" + +#if SOC_MIPI_DSI_SUPPORTED +#include "esp_check.h" +#include "esp_log.h" +#include "esp_lcd_panel_commands.h" +#include "esp_lcd_panel_interface.h" +#include "esp_lcd_panel_io.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_lcd_panel_vendor.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_lcd_st7123.h" + +#define ST7123_PAD_CONTROL (0xB7) +#define ST7123_DSI_2_LANE (0x03) +#define ST7123_DSI_3_4_LANE (0x02) + +#define ST7123_CMD_GS_BIT (1 << 0) +#define ST7123_CMD_SS_BIT (1 << 1) + +typedef struct { + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + uint8_t madctl_val; // save current value of LCD_CMD_MADCTL register + uint8_t colmod_val; // save surrent value of LCD_CMD_COLMOD register + const st7123_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; + uint8_t lane_num; + struct { + unsigned int reset_level: 1; + } flags; + // To save the original functions of MIPI DPI panel + esp_err_t (*del)(esp_lcd_panel_t *panel); + esp_err_t (*init)(esp_lcd_panel_t *panel); +} st7123_panel_t; + +static const char *TAG = "st7123"; + +static esp_err_t panel_st7123_del(esp_lcd_panel_t *panel); +static esp_err_t panel_st7123_init(esp_lcd_panel_t *panel); +static esp_err_t panel_st7123_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_st7123_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); +static esp_err_t panel_st7123_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_st7123_disp_on_off(esp_lcd_panel_t *panel, bool on_off); +static esp_err_t panel_st7123_sleep(esp_lcd_panel_t *panel, bool sleep); + +esp_err_t esp_lcd_new_panel_st7123(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, + esp_lcd_panel_handle_t *ret_panel) +{ + ESP_RETURN_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, TAG, "invalid arguments"); + st7123_vendor_config_t *vendor_config = (st7123_vendor_config_t *)panel_dev_config->vendor_config; + ESP_RETURN_ON_FALSE(vendor_config && vendor_config->mipi_config.dpi_config && vendor_config->mipi_config.dsi_bus, ESP_ERR_INVALID_ARG, TAG, + "invalid vendor config"); + + esp_err_t ret = ESP_OK; + st7123_panel_t *st7123 = (st7123_panel_t *)calloc(1, sizeof(st7123_panel_t)); + ESP_RETURN_ON_FALSE(st7123, ESP_ERR_NO_MEM, TAG, "no mem for st7123 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) { + gpio_config_t io_conf = { + .mode = GPIO_MODE_OUTPUT, + .pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num, + }; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + + switch (panel_dev_config->rgb_ele_order) { + case LCD_RGB_ELEMENT_ORDER_RGB: + st7123->madctl_val = 0; + break; + case LCD_RGB_ELEMENT_ORDER_BGR: + st7123->madctl_val |= LCD_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color space"); + break; + } + + switch (panel_dev_config->bits_per_pixel) { + case 16: // RGB565 + st7123->colmod_val = 0x55; + break; + case 18: // RGB666 + st7123->colmod_val = 0x66; + break; + case 24: // RGB888 + st7123->colmod_val = 0x77; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + st7123->io = io; + st7123->init_cmds = vendor_config->init_cmds; + st7123->init_cmds_size = vendor_config->init_cmds_size; + st7123->lane_num = vendor_config->mipi_config.lane_num; + st7123->reset_gpio_num = panel_dev_config->reset_gpio_num; + st7123->flags.reset_level = panel_dev_config->flags.reset_active_high; + + // Create MIPI DPI panel + ESP_GOTO_ON_ERROR(esp_lcd_new_panel_dpi(vendor_config->mipi_config.dsi_bus, vendor_config->mipi_config.dpi_config, ret_panel), err, TAG, + "create MIPI DPI panel failed"); + ESP_LOGD(TAG, "new MIPI DPI panel @%p", *ret_panel); + + // Save the original functions of MIPI DPI panel + st7123->del = (*ret_panel)->del; + st7123->init = (*ret_panel)->init; + // Overwrite the functions of MIPI DPI panel + (*ret_panel)->del = panel_st7123_del; + (*ret_panel)->init = panel_st7123_init; + (*ret_panel)->reset = panel_st7123_reset; + (*ret_panel)->mirror = panel_st7123_mirror; + (*ret_panel)->invert_color = panel_st7123_invert_color; + (*ret_panel)->disp_on_off = panel_st7123_disp_on_off; + (*ret_panel)->disp_sleep = panel_st7123_sleep; + (*ret_panel)->user_data = st7123; + ESP_LOGD(TAG, "new st7123 panel @%p", st7123); + + return ESP_OK; + + err: + if (st7123) { + if (panel_dev_config->reset_gpio_num >= 0) { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(st7123); + } + return ret; +} + +static const st7123_lcd_init_cmd_t vendor_specific_init_default[] = { + // {cmd, { data }, data_size, delay_ms} + // TODO: + {0x60, (uint8_t []){0x71,0x23,0xa2}, 3, 0}, + {0x60, (uint8_t []){0x71,0x23,0xa3}, 3, 0}, + {0x60, (uint8_t []){0x71,0x23,0xa4}, 3, 0}, + {0xA4, (uint8_t []){0x31}, 1, 0}, + {0xD7, (uint8_t []){0x10,0x0A,0x10,0x2A,0x80,0x80}, 6, 0}, + {0x90, (uint8_t []){0x71,0x23,0x5A,0x20,0x24,0x09,0x09}, 7, 0}, + {0xA3, (uint8_t []){0x80,0x01,0x88,0x30,0x05,0x00,0x00,0x00,0x00,0x00,0x46,0x00,0x00,0x1E,0x5C,0x1E,0x80,0x00,0x4F,0x05,0x00,0x00,0x00,0x00,0x00,0x46,0x00,0x00,0x1E,0x5C,0x1E,0x80,0x00,0x6F,0x58,0x00,0x00,0x00,0xFF}, 40, 0}, + {0xA6, (uint8_t []){0x03,0x00,0x24,0x55,0x36,0x00,0x39,0x00,0x6E,0x6E,0x91,0xFF,0x00,0x24,0x55,0x38,0x00,0x37,0x00,0x6E,0x6E,0x91,0xFF,0x00,0x24,0x11,0x00,0x00,0x00,0x00,0x6E,0x6E,0x91,0xFF,0x00,0xEC,0x11,0x00,0x03,0x00,0x03,0x6E,0x6E,0xFF,0xFF,0x00,0x08,0x80,0x08,0x80,0x06,0x00,0x00,0x00,0x00}, 55, 0}, + {0xA7, (uint8_t []){0x19,0x19,0x80,0x64,0x40,0x07,0x16,0x40,0x00,0x44,0x03,0x6E,0x6E,0x91,0xFF,0x08,0x80,0x64,0x40,0x25,0x34,0x40,0x00,0x02,0x01,0x6E,0x6E,0x91,0xFF,0x08,0x80,0x64,0x40,0x00,0x00,0x40,0x00,0x00,0x00,0x6E,0x6E,0x91,0xFF,0x08,0x80,0x64,0x40,0x00,0x00,0x00,0x00,0x20,0x00,0x6E,0x6E,0x84,0xFF,0x08,0x80,0x44}, 60, 0}, + {0xAC, (uint8_t []){0x03,0x19,0x19,0x18,0x18,0x06,0x13,0x13,0x11,0x11,0x08,0x08,0x0A,0x0A,0x1C,0x1C,0x07,0x07,0x00,0x00,0x02,0x02,0x01,0x19,0x19,0x18,0x18,0x06,0x12,0x12,0x10,0x10,0x09,0x09,0x0B,0x0B,0x1C,0x1C,0x07,0x07,0x03,0x03,0x01,0x01}, 44, 0}, + {0xAD, (uint8_t []){0xF0,0x00,0x46,0x00,0x03,0x50,0x50,0xFF,0xFF,0xF0,0x40,0x06,0x01,0x07,0x42,0x42,0xFF,0xFF,0x01,0x00,0x00,0xFF,0xFF,0xFF,0xFF}, 25, 0}, + {0xAE, (uint8_t []){0xFE,0x3F,0x3F,0xFE,0x3F,0x3F,0x00}, 7, 0}, + {0xB2, (uint8_t []){0x15,0x19,0x05,0x23,0x49,0xAF,0x03,0x2E,0x5C,0xD2,0xFF,0x10,0x20,0xFD,0x20,0xC0,0x00}, 17, 0}, + {0xE8, (uint8_t []){0x20,0x6F,0x04,0x97,0x97,0x3E,0x04,0xDC,0xDC,0x3E,0x06,0xFA,0x26,0x3E}, 15, 0}, + {0x75, (uint8_t []){0x03,0x04}, 2, 0}, + {0xE7, (uint8_t []){0x3B,0x00,0x00,0x7C,0xA1,0x8C,0x20,0x1A,0xF0,0xB1,0x50,0x00,0x50,0xB1,0x50,0xB1,0x50,0xD8,0x00,0x55,0x00,0xB1,0x00,0x45,0xC9,0x6A,0xFF,0x5A,0xD8,0x18,0x88,0x15,0xB1,0x01,0x01,0x77}, 36, 0}, + {0xEA, (uint8_t []){0x13,0x00,0x04,0x00,0x00,0x00,0x00,0x2C}, 8, 0}, + {0xB0, (uint8_t []){0x22,0x43,0x11,0x61,0x25,0x43,0x43}, 7, 0}, + {0xb7, (uint8_t []){0x00,0x00,0x73,0x73}, 0x04, 0}, + {0xBF, (uint8_t []){0xA6,0XAA}, 2, 0}, + {0xA9, (uint8_t []){0x00,0x00,0x73,0xFF,0x00,0x00,0x03,0x00,0x00,0x03}, 10, 0}, + {0xC8, (uint8_t []){0x00,0x00,0x10,0x1F,0x36,0x00,0x5D,0x04,0x9D,0x05,0x10,0xF2,0x06,0x60,0x03,0x11,0xAD,0x00,0xEF,0x01,0x22,0x2E,0x0E,0x74,0x08,0x32,0xDC,0x09,0x33,0x0F,0xF3,0x77,0x0D,0xB0,0xDC,0x03,0xFF}, 37, 0}, + {0xC9, (uint8_t []){0x00,0x00,0x10,0x1F,0x36,0x00,0x5D,0x04,0x9D,0x05,0x10,0xF2,0x06,0x60,0x03,0x11,0xAD,0x00,0xEF,0x01,0x22,0x2E,0x0E,0x74,0x08,0x32,0xDC,0x09,0x33,0x0F,0xF3,0x77,0x0D,0xB0,0xDC,0x03,0xFF}, 37, 0}, + {0x36, (uint8_t []){0x03}, 1, 0}, + {0x11, (uint8_t []){0x00}, 1, 100}, + {0x29, (uint8_t []){0x00}, 1, 0}, + {0x35, (uint8_t []){0x00}, 1, 100}, + //============ Gamma END=========== +}; + +static esp_err_t panel_st7123_del(esp_lcd_panel_t *panel) +{ + st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + + if (st7123->reset_gpio_num >= 0) { + gpio_reset_pin(st7123->reset_gpio_num); + } + // Delete MIPI DPI panel + st7123->del(panel); + ESP_LOGD(TAG, "del st7123 panel @%p", st7123); + free(st7123); + + return ESP_OK; +} + +static esp_err_t panel_st7123_init(esp_lcd_panel_t *panel) +{ + st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = st7123->io; + const st7123_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + + // switch (st7123->lane_num) { + // case 0: + // case 2: + // lane_command = ST7123_DSI_2_LANE; + // break; + // case 3: + // case 4: + // lane_command = ST7123_DSI_3_4_LANE; + // break; + // default: + // ESP_LOGE(TAG, "Invalid lane number %d", st7123->lane_num); + // return ESP_ERR_INVALID_ARG; + // } + + uint8_t ID[3]; + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_rx_param(io, 0x04, ID, 3), TAG, "read ID failed"); + ESP_LOGI(TAG, "LCD ID: %02X %02X %02X", ID[0], ID[1], ID[2]); + + // // For modifying MIPI-DSI lane settings + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, ST7123_PAD_CONTROL, (uint8_t[]) { + // lane_command, + // }, 1), TAG, "send command failed"); + + // // back to CMD_Page 0 + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, ST7123_CMD_CNDBKxSEL, (uint8_t[]) { + // ST7123_CMD_BKxSEL_BYTE0, ST7123_CMD_BKxSEL_BYTE1, ST7123_CMD_BKxSEL_BYTE2_PAGE0 + // }, 3), TAG, "send command failed"); + // // exit sleep mode + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SLPOUT, NULL, 0), TAG, + // "io tx param failed"); + // vTaskDelay(pdMS_TO_TICKS(120)); + + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]) { + // st7123->madctl_val, + // }, 1), TAG, "send command failed"); + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]) { + // st7123->colmod_val, + // }, 1), TAG, "send command failed"); + + // vendor specific initialization, it can be different between manufacturers + // should consult the LCD supplier for initialization sequence code + if (st7123->init_cmds) { + init_cmds = st7123->init_cmds; + init_cmds_size = st7123->init_cmds_size; + } else { + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(st7123_lcd_init_cmd_t); + } + + for (int i = 0; i < init_cmds_size; i++) { + // Check if the command has been used or conflicts with the internal + // if (is_command0_enable && init_cmds[i].data_bytes > 0) { + // switch (init_cmds[i].cmd) { + // case LCD_CMD_MADCTL: + // is_cmd_overwritten = true; + // st7123->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + // break; + // case LCD_CMD_COLMOD: + // is_cmd_overwritten = true; + // st7123->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + // break; + // default: + // is_cmd_overwritten = false; + // break; + // } + + // if (is_cmd_overwritten) { + // is_cmd_overwritten = false; + // ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", + // init_cmds[i].cmd); + // } + // } + + // Send command + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + + // if ((init_cmds[i].cmd == ST7123_CMD_CNDBKxSEL) && (((uint8_t *)init_cmds[i].data)[2] == ST7123_CMD_BKxSEL_BYTE2_PAGE0)) { + // is_command0_enable = true; + // } else if ((init_cmds[i].cmd == ST7123_CMD_CNDBKxSEL) && (((uint8_t *)init_cmds[i].data)[2] != ST7123_CMD_BKxSEL_BYTE2_PAGE0)) { + // is_command0_enable = false; + // } + } + ESP_LOGD(TAG, "send init commands success"); + + ESP_RETURN_ON_ERROR(st7123->init(panel), TAG, "init MIPI DPI panel failed"); + + return ESP_OK; +} + +static esp_err_t panel_st7123_reset(esp_lcd_panel_t *panel) +{ + st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + esp_lcd_panel_io_handle_t io = st7123->io; + + // Perform hardware reset + if (st7123->reset_gpio_num >= 0) { + gpio_set_level(st7123->reset_gpio_num, st7123->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(50)); + gpio_set_level(st7123->reset_gpio_num, !st7123->flags.reset_level); + vTaskDelay(pdMS_TO_TICKS(50)); + } else if (io) { // Perform software reset + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(20)); + } + + return ESP_OK; +} + +static esp_err_t panel_st7123_invert_color(esp_lcd_panel_t *panel, bool invert_color_data) +{ + // st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + // esp_lcd_panel_io_handle_t io = st7123->io; + // uint8_t command = 0; + + // ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + // if (invert_color_data) { + // command = LCD_CMD_INVON; + // } else { + // command = LCD_CMD_INVOFF; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + + return ESP_OK; +} + +static esp_err_t panel_st7123_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + // st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + // esp_lcd_panel_io_handle_t io = st7123->io; + // uint8_t madctl_val = st7123->madctl_val; + + // ESP_RETURN_ON_FALSE(io, ESP_ERR_INVALID_STATE, TAG, "invalid panel IO"); + + // // Control mirror through LCD command + // if (mirror_x) { + // madctl_val |= ST7123_CMD_GS_BIT; + // } else { + // madctl_val &= ~ST7123_CMD_GS_BIT; + // } + // if (mirror_y) { + // madctl_val |= ST7123_CMD_SS_BIT; + // } else { + // madctl_val &= ~ST7123_CMD_SS_BIT; + // } + + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t []) { + // madctl_val + // }, 1), TAG, "send command failed"); + // st7123->madctl_val = madctl_val; + + return ESP_OK; +} + +static esp_err_t panel_st7123_disp_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + // st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + // esp_lcd_panel_io_handle_t io = st7123->io; + // int command = 0; + + // if (on_off) { + // command = LCD_CMD_DISPON; + // } else { + // command = LCD_CMD_DISPOFF; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_st7123_sleep(esp_lcd_panel_t *panel, bool sleep) +{ + // st7123_panel_t *st7123 = (st7123_panel_t *)panel->user_data; + // esp_lcd_panel_io_handle_t io = st7123->io; + // int command = 0; + + // if (sleep) { + // command = LCD_CMD_SLPIN; + // } else { + // command = LCD_CMD_SLPOUT; + // } + // ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + // vTaskDelay(pdMS_TO_TICKS(100)); + + return ESP_OK; +} +#endif // SOC_MIPI_DSI_SUPPORTED diff --git a/main/boards/m5stack-tab5/esp_lcd_st7123.h b/main/boards/m5stack-tab5/esp_lcd_st7123.h new file mode 100644 index 0000000..27c514e --- /dev/null +++ b/main/boards/m5stack-tab5/esp_lcd_st7123.h @@ -0,0 +1,125 @@ +/* + * SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * @file + * @brief ESP LCD: ST7123 + */ + + #pragma once + + #include + #include "soc/soc_caps.h" + + #if SOC_MIPI_DSI_SUPPORTED + #include "esp_lcd_panel_vendor.h" + #include "esp_lcd_mipi_dsi.h" + + #ifdef __cplusplus + extern "C" { + #endif + + /** + * @brief LCD panel initialization commands. + * + */ + typedef struct { + int cmd; /* +#include "esp_check.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_lcd_panel_ops.h" +#include "esp_ldo_regulator.h" +#include +#include +#include +#include +#include "i2c_device.h" +#include "esp_lcd_touch_gt911.h" +#include "esp_lcd_touch_st7123.h" +#include + +#define TAG "M5StackTab5Board" + +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR +#define LCD_MIPI_DSI_PHY_PWR_LDO_CHAN 3 // LDO_VO3 is connected to VDD_MIPI_DPHY +#define LCD_MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV 2500 +#define ST7123_TOUCH_I2C_ADDRESS 0x55 + + +// PI4IO registers +#define PI4IO_REG_CHIP_RESET 0x01 +#define PI4IO_REG_IO_DIR 0x03 +#define PI4IO_REG_OUT_SET 0x05 +#define PI4IO_REG_OUT_H_IM 0x07 +#define PI4IO_REG_IN_DEF_STA 0x09 +#define PI4IO_REG_PULL_EN 0x0B +#define PI4IO_REG_PULL_SEL 0x0D +#define PI4IO_REG_IN_STA 0x0F +#define PI4IO_REG_INT_MASK 0x11 +#define PI4IO_REG_IRQ_STA 0x13 + +// Bit manipulation macros +#define setbit(x, bit) ((x) |= (1U << (bit))) +#define clrbit(x, bit) ((x) &= ~(1U << (bit))) + +class Pi4ioe1 : public I2cDevice { +public: + Pi4ioe1(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(PI4IO_REG_CHIP_RESET, 0xFF); + uint8_t data = ReadReg(PI4IO_REG_CHIP_RESET); + WriteReg(PI4IO_REG_IO_DIR, 0b01111111); // 0: input 1: output + WriteReg(PI4IO_REG_OUT_H_IM, 0b00000000); // 使用到的引脚关闭 High-Impedance + WriteReg(PI4IO_REG_PULL_SEL, 0b01111111); // pull up/down select, 0 down, 1 up + WriteReg(PI4IO_REG_PULL_EN, 0b01111111); // pull up/down enable, 0 disable, 1 enable + WriteReg(PI4IO_REG_IN_DEF_STA, 0b10000000); // P1, P7 默认高电平 + WriteReg(PI4IO_REG_INT_MASK, 0b01111111); // P7 中断使能 0 enable, 1 disable + WriteReg(PI4IO_REG_OUT_SET, 0b01110110); // Output Port Register P1(SPK_EN), P2(EXT5V_EN), P4(LCD_RST), P5(TP_RST), P6(CAM)RST 输出高电平 + } + + uint8_t ReadOutSet() { return ReadReg(PI4IO_REG_OUT_SET); } + void WriteOutSet(uint8_t value) { WriteReg(PI4IO_REG_OUT_SET, value); } +}; + +class Pi4ioe2 : public I2cDevice { +public: + Pi4ioe2(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + WriteReg(PI4IO_REG_CHIP_RESET, 0xFF); + uint8_t data = ReadReg(PI4IO_REG_CHIP_RESET); + WriteReg(PI4IO_REG_IO_DIR, 0b10111001); // 0: input 1: output + WriteReg(PI4IO_REG_OUT_H_IM, 0b00000110); // 使用到的引脚关闭 High-Impedance + WriteReg(PI4IO_REG_PULL_SEL, 0b10111001); // pull up/down select, 0 down, 1 up + WriteReg(PI4IO_REG_PULL_EN, 0b11111001); // pull up/down enable, 0 disable, 1 enable + WriteReg(PI4IO_REG_IN_DEF_STA, 0b01000000); // P6 默认高电平 + WriteReg(PI4IO_REG_INT_MASK, 0b10111111); // P6 中断使能 0 enable, 1 disable + WriteReg(PI4IO_REG_OUT_SET, 0b10001001); // Output Port Register P0(WLAN_PWR_EN), P3(USB5V_EN), P7(CHG_EN) 输出高电平 + } + + uint8_t ReadOutSet() { return ReadReg(PI4IO_REG_OUT_SET); } + void WriteOutSet(uint8_t value) { WriteReg(PI4IO_REG_OUT_SET, value); } +}; + +class M5StackTab5Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + Esp32Camera* camera_ = nullptr; + Pi4ioe1* pi4ioe1_; + Pi4ioe2* pi4ioe2_; + esp_lcd_touch_handle_t touch_ = nullptr; + + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power() { + esp_ldo_channel_handle_t ldo_mipi_phy = NULL; + esp_ldo_channel_config_t ldo_mipi_phy_config = { + .chan_id = LCD_MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = LCD_MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + return esp_ldo_acquire_channel(&ldo_mipi_phy_config, &ldo_mipi_phy); + } + + void I2cDetect() { + uint8_t address; + printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n"); + for (int i = 0; i < 128; i += 16) { + printf("%02x: ", i); + for (int j = 0; j < 16; j++) { + fflush(stdout); + address = i + j; + esp_err_t ret = i2c_master_probe(i2c_bus_, address, pdMS_TO_TICKS(200)); + if (ret == ESP_OK) { + printf("%02x ", address); + } else if (ret == ESP_ERR_TIMEOUT) { + printf("UU "); + } else { + printf("-- "); + } + } + printf("\r\n"); + } + } + + void InitializePi4ioe() { + ESP_LOGI(TAG, "Init I/O Exapander PI4IOE"); + pi4ioe1_ = new Pi4ioe1(i2c_bus_, 0x43); + pi4ioe2_ = new Pi4ioe2(i2c_bus_, 0x44); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeGt911TouchPad() { + ESP_LOGI(TAG, "Init GT911"); + + /* Initialize Touch Panel */ + ESP_LOGI(TAG, "Initialize touch IO (I2C)"); + const esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = TOUCH_INT_GPIO, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.dev_addr = ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS_BACKUP; // 更改 GT911 地址 + tp_io_config.scl_speed_hz = 100000; + esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle); + esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &touch_); + } + + void InitializeIli9881cDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGI(TAG, "Turn on the power for MIPI DSI PHY"); + esp_ldo_channel_handle_t ldo_mipi_phy = NULL; + esp_ldo_channel_config_t ldo_mipi_phy_config = { + .chan_id = LCD_MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = LCD_MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + ESP_ERROR_CHECK(esp_ldo_acquire_channel(&ldo_mipi_phy_config, &ldo_mipi_phy)); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + esp_lcd_dsi_bus_handle_t mipi_dsi_bus; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 900, // 900MHz + }; + ESP_ERROR_CHECK(esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus)); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_dbi_io_config_t dbi_config = { + .virtual_channel = 0, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &panel_io)); + + ESP_LOGI(TAG, "Install LCD driver of ili9881c"); + esp_lcd_dpi_panel_config_t dpi_config = { + .virtual_channel = 0, + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 60, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 2, + .video_timing = { + .h_size = DISPLAY_WIDTH, + .v_size = DISPLAY_HEIGHT, + .hsync_pulse_width = 40, + .hsync_back_porch = 140, + .hsync_front_porch = 40, + .vsync_pulse_width = 4, + .vsync_back_porch = 20, + .vsync_front_porch = 20, + }, + .flags = { + .use_dma2d = false, + }, + }; + + ili9881c_vendor_config_t vendor_config = { + .init_cmds = tab5_lcd_ili9881c_specific_init_code_default, + .init_cmds_size = sizeof(tab5_lcd_ili9881c_specific_init_code_default) / sizeof(tab5_lcd_ili9881c_specific_init_code_default[0]), + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + .lane_num = 2, + }, + }; + + esp_lcd_panel_dev_config_t lcd_dev_config = {}; + lcd_dev_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + lcd_dev_config.reset_gpio_num = -1; + lcd_dev_config.bits_per_pixel = 16; + lcd_dev_config.vendor_config = &vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ili9881c(panel_io, &lcd_dev_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + + display_ = new MipiLcdDisplay(panel_io, panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, + DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeSt7123Display() { + esp_err_t ret = ESP_OK; + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + + // Declare all config structures at the top to avoid goto issues + // Initialize with memset to avoid any initialization syntax that might confuse the compiler + esp_lcd_dsi_bus_config_t bus_config; + esp_lcd_dbi_io_config_t dbi_config; + esp_lcd_dpi_panel_config_t dpi_config; + st7123_vendor_config_t vendor_config; + esp_lcd_panel_dev_config_t lcd_dev_config; + + memset(&bus_config, 0, sizeof(bus_config)); + memset(&dbi_config, 0, sizeof(dbi_config)); + memset(&dpi_config, 0, sizeof(dpi_config)); + memset(&vendor_config, 0, sizeof(vendor_config)); + memset(&lcd_dev_config, 0, sizeof(lcd_dev_config)); + + ESP_ERROR_CHECK(bsp_enable_dsi_phy_power()); + + /* create MIPI DSI bus first, it will initialize the DSI PHY as well */ + bus_config.bus_id = 0; + bus_config.num_data_lanes = 2; // ST7123 uses 2 data lanes + bus_config.lane_bit_rate_mbps = 965; // ST7123 lane bitrate + ret = esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "New DSI bus init failed"); + goto err; + } + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel for ST7123"); + // we use DBI interface to send LCD commands and parameters + dbi_config.virtual_channel = 0; + dbi_config.lcd_cmd_bits = 8; // according to the LCD spec + dbi_config.lcd_param_bits = 8; // according to the LCD spec + ret = esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "New panel IO failed"); + goto err; + } + + ESP_LOGI(TAG, "Install LCD driver of ST7123"); + dpi_config.virtual_channel = 0; + dpi_config.dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT; + dpi_config.dpi_clock_freq_mhz = 70; // ST7123 DPI clock frequency + dpi_config.pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565; + dpi_config.num_fbs = 1; + dpi_config.video_timing.h_size = 720; + dpi_config.video_timing.v_size = 1280; + dpi_config.video_timing.hsync_pulse_width = 2; + dpi_config.video_timing.hsync_back_porch = 40; + dpi_config.video_timing.hsync_front_porch = 40; + dpi_config.video_timing.vsync_pulse_width = 2; + dpi_config.video_timing.vsync_back_porch = 8; + dpi_config.video_timing.vsync_front_porch = 220; + dpi_config.flags.use_dma2d = true; + + vendor_config.init_cmds = st7123_vendor_specific_init_default; + vendor_config.init_cmds_size = sizeof(st7123_vendor_specific_init_default) / sizeof(st7123_vendor_specific_init_default[0]); + vendor_config.mipi_config.dsi_bus = mipi_dsi_bus; + vendor_config.mipi_config.dpi_config = &dpi_config; + vendor_config.mipi_config.lane_num = 2; + + lcd_dev_config.reset_gpio_num = -1; + lcd_dev_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + lcd_dev_config.data_endian = LCD_RGB_DATA_ENDIAN_LITTLE; + lcd_dev_config.bits_per_pixel = 24; + lcd_dev_config.vendor_config = &vendor_config; + + // 使用实际的 ST7123 驱动函数 + ret = esp_lcd_new_panel_st7123(io, &lcd_dev_config, &disp_panel); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "New LCD panel ST7123 failed"); + goto err; + } + + ret = esp_lcd_panel_reset(disp_panel); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "LCD panel reset failed"); + goto err; + } + + ret = esp_lcd_panel_init(disp_panel); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "LCD panel init failed"); + goto err; + } + + ret = esp_lcd_panel_disp_on_off(disp_panel, true); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "LCD panel display on failed"); + goto err; + } + + display_ = new MipiLcdDisplay(io, disp_panel, 720, 1280, DISPLAY_OFFSET_X, + DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + ESP_LOGI(TAG, "ST7123 Display initialized with resolution %dx%d", 720, 1280); + + return; + + err: + if (disp_panel) { + esp_lcd_panel_del(disp_panel); + } + if (io) { + esp_lcd_panel_io_del(io); + } + if (mipi_dsi_bus) { + esp_lcd_del_dsi_bus(mipi_dsi_bus); + } + ESP_ERROR_CHECK(ret); + } + + void InitializeSt7123TouchPad() { + ESP_LOGI(TAG, "Init ST7123 Touch"); + + /* Initialize Touch Panel */ + ESP_LOGI(TAG, "Initialize touch IO (I2C)"); + const esp_lcd_touch_config_t tp_cfg = { + .x_max = 720, + .y_max = 1280, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = TOUCH_INT_GPIO, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = { + .dev_addr = 0x55, + .control_phase_bytes = 1, + .dc_bit_offset = 0, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .scl_speed_hz = 100000, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_st7123(tp_io_handle, &tp_cfg, &touch_)); + } + + void InitializeDisplay() { + // after tp reset, wait for 100ms to ensure the I2C bus is stable + vTaskDelay(pdMS_TO_TICKS(100)); + // 检测 ST7123 触摸屏 (I2C地址 0x55) + esp_err_t ret = i2c_master_probe(i2c_bus_, ST7123_TOUCH_I2C_ADDRESS, 200); + if (ret == ESP_OK) { + ESP_LOGI(TAG, "Detected ST7123 at 0x%02X, initializing ST7123 display", ST7123_TOUCH_I2C_ADDRESS); + InitializeSt7123Display(); + InitializeSt7123TouchPad(); + } else { + ESP_LOGI(TAG, "ST7123 not found at 0x%02X (ret=0x%x), using default ST7703+GT911", ST7123_TOUCH_I2C_ADDRESS, ret); + InitializeIli9881cDisplay(); + InitializeGt911TouchPad(); + } + } + + void InitializeCamera() { + esp_cam_sensor_xclk_handle_t xclk_handle = NULL; + esp_cam_sensor_xclk_config_t cam_xclk_config = {}; + +#if CONFIG_CAMERA_XCLK_USE_ESP_CLOCK_ROUTER + if (esp_cam_sensor_xclk_allocate(ESP_CAM_SENSOR_XCLK_ESP_CLOCK_ROUTER, &xclk_handle) == ESP_OK) { + cam_xclk_config.esp_clock_router_cfg.xclk_pin = CAMERA_MCLK; + cam_xclk_config.esp_clock_router_cfg.xclk_freq_hz = 12000000; // 12MHz + (void)esp_cam_sensor_xclk_start(xclk_handle, &cam_xclk_config); + } +#elif CONFIG_CAMERA_XCLK_USE_LEDC + if (esp_cam_sensor_xclk_allocate(ESP_CAM_SENSOR_XCLK_LEDC, &xclk_handle) == ESP_OK) { + cam_xclk_config.ledc_cfg.timer = LEDC_TIMER_0; + cam_xclk_config.ledc_cfg.clk_cfg = LEDC_AUTO_CLK; + cam_xclk_config.ledc_cfg.channel = LEDC_CHANNEL_0; + cam_xclk_config.ledc_cfg.xclk_freq_hz = 12000000; // 12MHz + cam_xclk_config.ledc_cfg.xclk_pin = CAMERA_MCLK; + (void)esp_cam_sensor_xclk_start(xclk_handle, &cam_xclk_config); + } +#endif + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 400000, + }; + + esp_video_init_csi_config_t csi_config = { + .sccb_config = sccb_config, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + }; + + esp_video_init_config_t video_config = { + .csi = &csi_config, + }; + + camera_ = new Esp32Camera(video_config); + } + +public: + M5StackTab5Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + I2cDetect(); + InitializePi4ioe(); + InitializeDisplay(); // Auto-detect and initialize display + touch + InitializeCamera(); + InitializeButtons(); + SetChargeQcEn(true); + SetChargeEn(true); + SetUsb5vEn(true); + SetExt5vEn(true); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Tab5AudioCodec audio_codec(i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8388_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + // BSP power control functions + void SetChargeQcEn(bool en) { + if (pi4ioe2_) { + uint8_t value = pi4ioe2_->ReadOutSet(); + if (en) { + clrbit(value, 5); // P5 = CHG_QC_EN (低电平使能) + } else { + setbit(value, 5); + } + pi4ioe2_->WriteOutSet(value); + } + } + + void SetChargeEn(bool en) { + if (pi4ioe2_) { + uint8_t value = pi4ioe2_->ReadOutSet(); + if (en) { + setbit(value, 7); // P7 = CHG_EN + } else { + clrbit(value, 7); + } + pi4ioe2_->WriteOutSet(value); + } + } + + void SetUsb5vEn(bool en) { + if (pi4ioe2_) { + uint8_t value = pi4ioe2_->ReadOutSet(); + if (en) { + setbit(value, 3); // P3 = USB5V_EN + } else { + clrbit(value, 3); + } + pi4ioe2_->WriteOutSet(value); + } + } + + void SetExt5vEn(bool en) { + if (pi4ioe1_) { + uint8_t value = pi4ioe1_->ReadOutSet(); + if (en) { + setbit(value, 2); // P2 = EXT5V_EN + } else { + clrbit(value, 2); + } + pi4ioe1_->WriteOutSet(value); + } + } +}; + + +DECLARE_BOARD(M5StackTab5Board); + diff --git a/main/boards/m5stack-tab5/sdkconfig.tab5 b/main/boards/m5stack-tab5/sdkconfig.tab5 new file mode 100644 index 0000000..70f759c --- /dev/null +++ b/main/boards/m5stack-tab5/sdkconfig.tab5 @@ -0,0 +1,14 @@ +# This file was generated using idf.py save-defconfig. It can be edited manually. +# Espressif IoT Development Framework (ESP-IDF) 5.5.1 Project Minimal Configuration +# +CONFIG_BOARD_TYPE_M5STACK_CORE_TAB5=y + +CONFIG_XIAOZHI_ENABLE_ROTATE_CAMERA_IMAGE=y +CONFIG_CAMERA_SC202CS=y + +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_CMD_SLOT_1=13 +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_CLK_SLOT_1=12 +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D0_SLOT_1=11 +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D1_4BIT_BUS_SLOT_1=10 +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D2_4BIT_BUS_SLOT_1=9 +CONFIG_ESP_HOSTED_PRIV_SDIO_PIN_D3_4BIT_BUS_SLOT_1=8 diff --git a/main/boards/m5stack-tab5/tab5_audio_codec.cc b/main/boards/m5stack-tab5/tab5_audio_codec.cc new file mode 100644 index 0000000..74dfe2e --- /dev/null +++ b/main/boards/m5stack-tab5/tab5_audio_codec.cc @@ -0,0 +1,243 @@ +#include "tab5_audio_codec.h" + +#include +#include +#include + +#define TAG "Tab5AudioCodec" + +Tab5AudioCodec::Tab5AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8388_addr, uint8_t es7210_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + input_gain_ = 30; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = (i2c_port_t)1, + .addr = es8388_addr, + .bus_handle = i2c_master_handle, + }; + out_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(out_ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + es8388_codec_cfg_t es8388_cfg = {}; + es8388_cfg.ctrl_if = out_ctrl_if_; + es8388_cfg.gpio_if = gpio_if_; + es8388_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_DAC; + es8388_cfg.master_mode = true; + es8388_cfg.pa_pin = -1; // PI4IOE1 P1 控制 + es8388_cfg.pa_reverted = false; + es8388_cfg.hw_gain.pa_voltage = 5.0; + es8388_cfg.hw_gain.codec_dac_voltage = 3.3; + out_codec_if_ = es8388_codec_new(&es8388_cfg); + assert(out_codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = out_codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + + // Input + i2c_cfg.addr = es7210_addr; + in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7210_codec_cfg_t es7210_cfg = {}; + es7210_cfg.ctrl_if = in_ctrl_if_; + es7210_cfg.mic_selected = ES7210_SEL_MIC1 | ES7210_SEL_MIC2 | ES7210_SEL_MIC3 | ES7210_SEL_MIC4; + in_codec_if_ = es7210_codec_new(&es7210_cfg); + assert(in_codec_if_ != NULL); + + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + dev_cfg.codec_if = in_codec_if_; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + + ESP_LOGI(TAG, "Tab5 AudioDevice initialized"); +} + +Tab5AudioCodec::~Tab5AudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void Tab5AudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = 6, + .dma_frame_num = 240, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = I2S_GPIO_UNUSED, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + i2s_tdm_config_t tdm_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)input_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256, + .bclk_div = 8, + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_STEREO, + .slot_mask = i2s_tdm_slot_mask_t(I2S_TDM_SLOT0 | I2S_TDM_SLOT1 | I2S_TDM_SLOT2 | I2S_TDM_SLOT3), + .ws_width = I2S_TDM_AUTO_WS_WIDTH, + .ws_pol = false, + .bit_shift = true, + .left_align = false, + .big_endian = false, + .bit_order_lsb = false, + .skip_mask = false, + .total_slot = I2S_TDM_AUTO_SLOT_NUM + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = I2S_GPIO_UNUSED, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + ESP_ERROR_CHECK(i2s_channel_init_tdm_mode(rx_handle_, &tdm_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void Tab5AudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void Tab5AudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 4, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + if (input_reference_) { + fs.channel_mask |= ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1); + } + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_channel_gain(input_dev_, ESP_CODEC_DEV_MAKE_CHANNEL_MASK(0), input_gain_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void Tab5AudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + } + AudioCodec::EnableOutput(enable); +} + +int Tab5AudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int Tab5AudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} diff --git a/main/boards/m5stack-tab5/tab5_audio_codec.h b/main/boards/m5stack-tab5/tab5_audio_codec.h new file mode 100644 index 0000000..4e45589 --- /dev/null +++ b/main/boards/m5stack-tab5/tab5_audio_codec.h @@ -0,0 +1,37 @@ +#ifndef _TAB5_AUDIO_CODEC_H +#define _TAB5_AUDIO_CODEC_H + +#include "audio_codec.h" +#include +#include + + +class Tab5AudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + Tab5AudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8388_addr, uint8_t es7210_addr, bool input_reference); + virtual ~Tab5AudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _TAB5_AUDIO_CODEC_H diff --git a/main/boards/magiclick-2p4/config.h b/main/boards/magiclick-2p4/config.h new file mode 100644 index 0000000..bc37001 --- /dev/null +++ b/main/boards/magiclick-2p4/config.h @@ -0,0 +1,50 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_11 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_12 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_4 // pcb v2.4不起作用,适用于2.4A +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_5 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_6 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +//led power +#define BUILTIN_LED_POWER GPIO_NUM_39 // 低电平有效 +#define BUILTIN_LED_POWER_OUTPUT_INVERT true + +#define BUILTIN_LED_NUM 2 +#define BUILTIN_LED_GPIO GPIO_NUM_38 + +#define MAIN_BUTTON_GPIO GPIO_NUM_21 +#define LEFT_BUTTON_GPIO GPIO_NUM_0 +#define RIGHT_BUTTON_GPIO GPIO_NUM_47 + +// display +#define DISPLAY_SDA_PIN GPIO_NUM_15 +#define DISPLAY_SCL_PIN GPIO_NUM_16 +#define DISPLAY_CS_PIN GPIO_NUM_17 +#define DISPLAY_DC_PIN GPIO_NUM_18 +#define DISPLAY_RST_PIN GPIO_NUM_14 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/magiclick-2p4/config.json b/main/boards/magiclick-2p4/config.json new file mode 100644 index 0000000..f416c2a --- /dev/null +++ b/main/boards/magiclick-2p4/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "magiclick-2p4", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/magiclick-2p4/magiclick_2p4_board.cc b/main/boards/magiclick-2p4/magiclick_2p4_board.cc new file mode 100644 index 0000000..770884b --- /dev/null +++ b/main/boards/magiclick-2p4/magiclick_2p4_board.cc @@ -0,0 +1,270 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/circular_strip.h" +#include "config.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include + +#include "../magiclick-2p5/power_manager.h" +#include "power_save_timer.h" + +#define TAG "magiclick_2p4" + +class NV3023Display : public SpiLcdDisplay { +public: + NV3023Display(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + // 只需要覆盖颜色相关的样式 + auto screen = lv_disp_get_scr_act(lv_disp_get_default()); + lv_obj_set_style_text_color(screen, lv_color_black(), 0); + + // 设置容器背景色 + lv_obj_set_style_bg_color(container_, lv_color_black(), 0); + + // 设置状态栏背景色和文本颜色 + lv_obj_set_style_bg_color(status_bar_, lv_color_white(), 0); + lv_obj_set_style_text_color(network_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(notification_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(status_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(mute_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(battery_label_, lv_color_black(), 0); + + // 设置内容区背景色和文本颜色 + lv_obj_set_style_bg_color(content_, lv_color_black(), 0); + lv_obj_set_style_border_width(content_, 0, 0); + lv_obj_set_style_text_color(emoji_label_, lv_color_white(), 0); + lv_obj_set_style_text_color(chat_message_label_, lv_color_white(), 0); + } +}; + +class magiclick_2p4 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button main_button_; + Button left_button_; + Button right_button_; + NV3023Display* display_; + + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_48); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(240, 60, -1); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeButtons() { + main_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + main_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + Application::GetInstance().StartListening(); + }); + main_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + left_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + left_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + right_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + right_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + } + + void InitializeLedPower() { + // 设置GPIO模式 + gpio_reset_pin(BUILTIN_LED_POWER); + gpio_set_direction(BUILTIN_LED_POWER, GPIO_MODE_OUTPUT); + gpio_set_level(BUILTIN_LED_POWER, BUILTIN_LED_POWER_OUTPUT_INVERT ? 0 : 1); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeNv3023Display(){ + // esp_lcd_panel_io_handle_t panel_io = nullptr; + // esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片NV3023 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_nv3023(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + display_ = new NV3023Display(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + magiclick_2p4() : + main_button_(MAIN_BUTTON_GPIO), + left_button_(LEFT_BUTTON_GPIO), + right_button_(RIGHT_BUTTON_GPIO) { + InitializeLedPower(); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeButtons(); + InitializeSpi(); + InitializeNv3023Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static CircularStrip led(BUILTIN_LED_GPIO, BUILTIN_LED_NUM); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(magiclick_2p4); diff --git a/main/boards/magiclick-2p5/config.h b/main/boards/magiclick-2p5/config.h new file mode 100644 index 0000000..3b8cce7 --- /dev/null +++ b/main/boards/magiclick-2p5/config.h @@ -0,0 +1,55 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_11 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_12 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_4 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_5 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_6 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +//led power +#define BUILTIN_LED_POWER GPIO_NUM_39 // 低电平有效 +#define BUILTIN_LED_POWER_OUTPUT_INVERT true + +#define BUILTIN_LED_NUM 2 +#define BUILTIN_LED_GPIO GPIO_NUM_38 + +#define MAIN_BUTTON_GPIO GPIO_NUM_21 +#define LEFT_BUTTON_GPIO GPIO_NUM_0 +#define RIGHT_BUTTON_GPIO GPIO_NUM_47 + +// display +#define DISPLAY_SDA_PIN GPIO_NUM_16 +#define DISPLAY_SCL_PIN GPIO_NUM_15 +#define DISPLAY_CS_PIN GPIO_NUM_14 +#define DISPLAY_DC_PIN GPIO_NUM_18 +#define DISPLAY_RST_PIN GPIO_NUM_17 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#define ML307_RX_PIN GPIO_NUM_42 +#define ML307_TX_PIN GPIO_NUM_44 +#define ML307_POWER_PIN GPIO_NUM_40 +#define ML307_POWER_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/magiclick-2p5/config.json b/main/boards/magiclick-2p5/config.json new file mode 100644 index 0000000..6220641 --- /dev/null +++ b/main/boards/magiclick-2p5/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "magiclick-2p5", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/magiclick-2p5/magiclick_2p5_board.cc b/main/boards/magiclick-2p5/magiclick_2p5_board.cc new file mode 100644 index 0000000..1db21fa --- /dev/null +++ b/main/boards/magiclick-2p5/magiclick_2p5_board.cc @@ -0,0 +1,326 @@ +#include "dual_network_board.h" +#include "display/lcd_display.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/circular_strip.h" +#include "config.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "power_manager.h" +#include "power_save_timer.h" +#include "esp_wifi.h" + +#define TAG "magiclick_2p5" + +class GC9107Display : public SpiLcdDisplay { +public: + GC9107Display(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + } +}; + +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; + +class magiclick_2p5 : public DualNetworkBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button main_button_; + Button left_button_; + Button right_button_; + GC9107Display* display_; + + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_48); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(240, 60, -1); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + + power_save_timer_->SetEnabled(true); + } + + void Enable4GModule() { + // enable the 4G module + gpio_reset_pin(ML307_POWER_PIN); + gpio_set_direction(ML307_POWER_PIN, GPIO_MODE_OUTPUT); + gpio_set_level(ML307_POWER_PIN, ML307_POWER_OUTPUT_INVERT ? 0 : 1); + } + void Disable4GModule() { + // enable the 4G module + gpio_reset_pin(ML307_POWER_PIN); + gpio_set_direction(ML307_POWER_PIN, GPIO_MODE_OUTPUT); + gpio_set_level(ML307_POWER_PIN, ML307_POWER_OUTPUT_INVERT ? 1 : 0); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void CheckNetType() { + if (GetNetworkType() == NetworkType::WIFI) { + Disable4GModule(); + } else if (GetNetworkType() == NetworkType::ML307) { + Enable4GModule(); + } + + } + + void InitializeButtons() { + main_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + Disable4GModule(); + } + } else if(GetNetworkType() == NetworkType::ML307) { + + Enable4GModule(); + // stop WiFi + esp_wifi_stop(); + } + }); + main_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + main_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + Application::GetInstance().StartListening(); + }); + main_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + left_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + left_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + + right_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + right_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + } + + void InitializeLedPower() { + // 设置GPIO模式 + gpio_reset_pin(BUILTIN_LED_POWER); + gpio_set_direction(BUILTIN_LED_POWER, GPIO_MODE_OUTPUT); + gpio_set_level(BUILTIN_LED_POWER, BUILTIN_LED_POWER_OUTPUT_INVERT ? 0 : 1); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeGc9107Display(){ + // esp_lcd_panel_io_handle_t panel_io = nullptr; + // esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片GC9107 + ESP_LOGD(TAG, "Install LCD driver"); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &gc9107_vendor_config; + + esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true)); + display_ = new GC9107Display(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + magiclick_2p5() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN, GPIO_NUM_NC, 0), + main_button_(MAIN_BUTTON_GPIO), + left_button_(LEFT_BUTTON_GPIO), + right_button_(RIGHT_BUTTON_GPIO) { + InitializeLedPower(); + CheckNetType(); + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeButtons(); + InitializeSpi(); + InitializeGc9107Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static CircularStrip led(BUILTIN_LED_GPIO, BUILTIN_LED_NUM); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(magiclick_2p5); diff --git a/main/boards/magiclick-2p5/power_manager.h b/main/boards/magiclick-2p5/power_manager.h new file mode 100644 index 0000000..5517a13 --- /dev/null +++ b/main/boards/magiclick-2p5/power_manager.h @@ -0,0 +1,195 @@ +#pragma once +#include +#include + +#include +#include +#include + +#define CHARGING_PIN GPIO_NUM_48 +#define CHARGING_ACTIVE_STATE 0 + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = CHARGING_PIN; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 0; + // ESP_LOGI("PowerManager", "new_charging_status: %s,is_charging_:%s", new_charging_status?"True":"False",is_charging_?"True":"False"); + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_6, &adc_value)); + ESP_LOGI("PowerManager", "ADC value: %d ", adc_value); + + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1985, 0}, + {2079, 20}, + {2141, 40}, + {2296, 60}, + {2420, 80}, + {2606, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_6, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 检测充电指示引脚 + if(gpio_get_level(charging_pin_) != CHARGING_ACTIVE_STATE) + { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/magiclick-c3-v2/config.h b/main/boards/magiclick-c3-v2/config.h new file mode 100644 index 0000000..5609bf6 --- /dev/null +++ b/main/boards/magiclick-c3-v2/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_8 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_10 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_11 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_3 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_4 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_NUM 1 +#define BUILTIN_LED_GPIO GPIO_NUM_0 + +#define BOOT_BUTTON_GPIO GPIO_NUM_2 + +//battery +#define BUILTIN_BATTERY_GPIO GPIO_NUM_1 + +// display +#define DISPLAY_SDA_PIN GPIO_NUM_13 +#define DISPLAY_SCL_PIN GPIO_NUM_12 +#define DISPLAY_CS_PIN GPIO_NUM_20 +#define DISPLAY_DC_PIN GPIO_NUM_21 +#define DISPLAY_RST_PIN GPIO_NUM_NC + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_9 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/magiclick-c3-v2/config.json b/main/boards/magiclick-c3-v2/config.json new file mode 100644 index 0000000..4503ebd --- /dev/null +++ b/main/boards/magiclick-c3-v2/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "magiclick-c3-v2", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_USE_ESP_WAKE_WORD=n" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/magiclick-c3-v2/magiclick_c3_v2_board.cc b/main/boards/magiclick-c3-v2/magiclick_c3_v2_board.cc new file mode 100644 index 0000000..19f564f --- /dev/null +++ b/main/boards/magiclick-c3-v2/magiclick_c3_v2_board.cc @@ -0,0 +1,232 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "config.h" +#include "power_save_timer.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define TAG "magiclick_c3_v2" + +class GC9107Display : public SpiLcdDisplay { +public: + GC9107Display(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + // 只需要覆盖颜色相关的样式 + auto screen = lv_disp_get_scr_act(lv_disp_get_default()); + lv_obj_set_style_text_color(screen, lv_color_black(), 0); + + // 设置容器背景色 + lv_obj_set_style_bg_color(container_, lv_color_black(), 0); + + // 设置状态栏背景色和文本颜色 + lv_obj_set_style_bg_color(status_bar_, lv_color_make(0x1e, 0x90, 0xff), 0); + lv_obj_set_style_text_color(network_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(notification_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(status_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(mute_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(battery_label_, lv_color_black(), 0); + + // 设置内容区背景色和文本颜色 + lv_obj_set_style_bg_color(content_, lv_color_black(), 0); + lv_obj_set_style_border_width(content_, 0, 0); + lv_obj_set_style_text_color(emoji_label_, lv_color_white(), 0); + lv_obj_set_style_text_color(chat_message_label_, lv_color_white(), 0); + } +}; + +static const gc9a01_lcd_init_cmd_t gc9107_lcd_init_cmds[] = { + // {cmd, { data }, data_size, delay_ms} + {0xfe, (uint8_t[]){0x00}, 0, 0}, + {0xef, (uint8_t[]){0x00}, 0, 0}, + {0xb0, (uint8_t[]){0xc0}, 1, 0}, + {0xb1, (uint8_t[]){0x80}, 1, 0}, + {0xb2, (uint8_t[]){0x27}, 1, 0}, + {0xb3, (uint8_t[]){0x13}, 1, 0}, + {0xb6, (uint8_t[]){0x19}, 1, 0}, + {0xb7, (uint8_t[]){0x05}, 1, 0}, + {0xac, (uint8_t[]){0xc8}, 1, 0}, + {0xab, (uint8_t[]){0x0f}, 1, 0}, + {0x3a, (uint8_t[]){0x05}, 1, 0}, + {0xb4, (uint8_t[]){0x04}, 1, 0}, + {0xa8, (uint8_t[]){0x08}, 1, 0}, + {0xb8, (uint8_t[]){0x08}, 1, 0}, + {0xea, (uint8_t[]){0x02}, 1, 0}, + {0xe8, (uint8_t[]){0x2A}, 1, 0}, + {0xe9, (uint8_t[]){0x47}, 1, 0}, + {0xe7, (uint8_t[]){0x5f}, 1, 0}, + {0xc6, (uint8_t[]){0x21}, 1, 0}, + {0xc7, (uint8_t[]){0x15}, 1, 0}, + {0xf0, + (uint8_t[]){0x1D, 0x38, 0x09, 0x4D, 0x92, 0x2F, 0x35, 0x52, 0x1E, 0x0C, + 0x04, 0x12, 0x14, 0x1f}, + 14, 0}, + {0xf1, + (uint8_t[]){0x16, 0x40, 0x1C, 0x54, 0xA9, 0x2D, 0x2E, 0x56, 0x10, 0x0D, + 0x0C, 0x1A, 0x14, 0x1E}, + 14, 0}, + {0xf4, (uint8_t[]){0x00, 0x00, 0xFF}, 3, 0}, + {0xba, (uint8_t[]){0xFF, 0xFF}, 2, 0}, +}; + +class magiclick_c3_v2 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + GC9107Display* display_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(160); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeGc9107Display(){ + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片GC9107 + ESP_LOGD(TAG, "Install LCD driver"); + gc9a01_vendor_config_t gc9107_vendor_config = { + .init_cmds = gc9107_lcd_init_cmds, + .init_cmds_size = sizeof(gc9107_lcd_init_cmds) / sizeof(gc9a01_lcd_init_cmd_t), + }; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &gc9107_vendor_config; + + esp_lcd_new_panel_gc9a01(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new GC9107Display(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + magiclick_c3_v2() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeGc9107Display(); + GetBacklight()->RestoreBrightness(); + + // 把 ESP32C3 的 VDD SPI 引脚作为普通 GPIO 口使用 + esp_efuse_write_field_bit(ESP_EFUSE_VDD_SPI_AS_GPIO); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(magiclick_c3_v2); diff --git a/main/boards/magiclick-c3/config.h b/main/boards/magiclick-c3/config.h new file mode 100644 index 0000000..90cd2b7 --- /dev/null +++ b/main/boards/magiclick-c3/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_8 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_10 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_11 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_3 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_4 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_NUM 1 +#define BUILTIN_LED_GPIO GPIO_NUM_0 + +#define BOOT_BUTTON_GPIO GPIO_NUM_2 + +//battery +#define BUILTIN_BATTERY_GPIO GPIO_NUM_1 + +// display +#define DISPLAY_SDA_PIN GPIO_NUM_12 +#define DISPLAY_SCL_PIN GPIO_NUM_13 +#define DISPLAY_CS_PIN GPIO_NUM_20 +#define DISPLAY_DC_PIN GPIO_NUM_21 +#define DISPLAY_RST_PIN GPIO_NUM_NC + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_9 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/magiclick-c3/config.json b/main/boards/magiclick-c3/config.json new file mode 100644 index 0000000..34d1471 --- /dev/null +++ b/main/boards/magiclick-c3/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "magiclick-c3", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_USE_ESP_WAKE_WORD=n" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/magiclick-c3/magiclick_c3_board.cc b/main/boards/magiclick-c3/magiclick_c3_board.cc new file mode 100644 index 0000000..373e661 --- /dev/null +++ b/main/boards/magiclick-c3/magiclick_c3_board.cc @@ -0,0 +1,190 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "config.h" +#include "power_save_timer.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "magiclick_c3" + +class NV3023Display : public SpiLcdDisplay { +public: + NV3023Display(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + // 只需要覆盖颜色相关的样式 + auto screen = lv_disp_get_scr_act(lv_disp_get_default()); + lv_obj_set_style_text_color(screen, lv_color_black(), 0); + + // 设置容器背景色 + lv_obj_set_style_bg_color(container_, lv_color_black(), 0); + + // 设置状态栏背景色和文本颜色 + lv_obj_set_style_bg_color(status_bar_, lv_color_white(), 0); + lv_obj_set_style_text_color(network_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(notification_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(status_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(mute_label_, lv_color_black(), 0); + lv_obj_set_style_text_color(battery_label_, lv_color_black(), 0); + + // 设置内容区背景色和文本颜色 + lv_obj_set_style_bg_color(content_, lv_color_black(), 0); + lv_obj_set_style_border_width(content_, 0, 0); + lv_obj_set_style_text_color(emoji_label_, lv_color_white(), 0); + lv_obj_set_style_text_color(chat_message_label_, lv_color_white(), 0); + } +}; + +class magiclick_c3 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + NV3023Display* display_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(160); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + boot_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeNv3023Display(){ + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片NV3023 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_nv3023(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new NV3023Display(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + magiclick_c3() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeButtons(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeNv3023Display(); + GetBacklight()->RestoreBrightness(); + + // 把 ESP32C3 的 VDD SPI 引脚作为普通 GPIO 口使用 + esp_efuse_write_field_bit(ESP_EFUSE_VDD_SPI_AS_GPIO); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(magiclick_c3); diff --git a/main/boards/minsi-k08-dual/README.md b/main/boards/minsi-k08-dual/README.md new file mode 100644 index 0000000..8b4a3e6 --- /dev/null +++ b/main/boards/minsi-k08-dual/README.md @@ -0,0 +1,36 @@ + +minsi-k08-wifi和minsi-k08-ml307是敏思科技推出的基于ESP32S3N16R8,搭载MAX98357音频功率放大器和INMP441全向麦克风模块,通过改造K08透明机甲小钢炮音箱而成的带有朋克风格的大喇叭大电池小智AI聊天机器人方案。 + +Minsi-k08 + + + + + + + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type ->敏思科技K08(DUAL) +``` + +**编译烧入:** + +```bash +idf.py build flash +``` \ No newline at end of file diff --git a/main/boards/minsi-k08-dual/config.h b/main/boards/minsi-k08-dual/config.h new file mode 100644 index 0000000..0bdecb0 --- /dev/null +++ b/main/boards/minsi-k08-dual/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_9 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_10 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_18 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_4 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_6 + +#define BUILTIN_LED_GPIO GPIO_NUM_40 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define TOUCH_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_47 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_46 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_7 +#define DISPLAY_MOSI_PIN GPIO_NUM_17 +#define DISPLAY_CLK_PIN GPIO_NUM_8 +#define DISPLAY_DC_PIN GPIO_NUM_15 +#define DISPLAY_RST_PIN GPIO_NUM_16 +#define DISPLAY_CS_PIN GPIO_NUM_NC + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY true +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 80 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +// A MCP Test: Control a lamp +#define LAMP_GPIO GPIO_NUM_18 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/minsi-k08-dual/config.json b/main/boards/minsi-k08-dual/config.json new file mode 100644 index 0000000..dd7f964 --- /dev/null +++ b/main/boards/minsi-k08-dual/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "minsi-k08-dual", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/minsi-k08-dual/minsi_k08_dual.cc b/main/boards/minsi-k08-dual/minsi_k08_dual.cc new file mode 100644 index 0000000..8fa0bba --- /dev/null +++ b/main/boards/minsi-k08-dual/minsi_k08_dual.cc @@ -0,0 +1,246 @@ +#include "dual_network_board.h" +//#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "mcp_server.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#define TAG "MINSI_K08_DUAL" + +class MINSI_K08_DUAL : public DualNetworkBoard { +private: + + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + //power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_ = new PowerManager(GPIO_NUM_3); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + //power_save_timer_->SetEnabled(false); + } + }); + } + + void InitializePowerSaveTimer() { + /*rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1);*/ + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + //rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + //rtc_gpio_hold_en(GPIO_NUM_21); + //esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + //esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + + //power_save_timer_->SetEnabled(false); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 3; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + // 物联网初始化,添加对 AI 可见设备 + void InitializeTools() { + static LampController lamp(LAMP_GPIO); + } + +public: + MINSI_K08_DUAL() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + //power_save_timer_->SetEnabled(false); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(MINSI_K08_DUAL); diff --git a/main/boards/minsi-k08-dual/power_manager.h b/main/boards/minsi-k08-dual/power_manager.h new file mode 100644 index 0000000..8ecdebc --- /dev/null +++ b/main/boards/minsi-k08-dual/power_manager.h @@ -0,0 +1,187 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + //bool new_charging_status = 0; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {894, 0}, + {954, 20}, + {1020, 40}, + {1084, 60}, + {1144, 80}, + {1234, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/mixgo-nova/README.md b/main/boards/mixgo-nova/README.md new file mode 100644 index 0000000..8a992ef --- /dev/null +++ b/main/boards/mixgo-nova/README.md @@ -0,0 +1,72 @@ +# Mixgo_Nova(元控·青春) 开发板 + +Mixgo_Nova + +‌**[Mixgo_Nova](https://mixly.cn/fredqian/mixgo_nova)**‌ 是一款专为物联网、教育及创客项目设计的多功能开发板,集成丰富传感器与无线通信模块,支持图形化编程(Mixly)和离线语音交互,适合快速原型开发与教学。 + +--- + +## 🛠️ 编译配置命令 + +**ES8374 CODE MIC采集问题:** + +``` +managed_components\espressif__esp_codec_dev\device\es8374 + +static int es8374_config_adc_input(audio_codec_es8374_t *codec, es_adc_input_t input) +{ + int ret = 0; + int reg = 0; + ret |= es8374_read_reg(codec, 0x21, ®); + if (ret == 0) { + reg = (reg & 0xcf) | 0x24; + ret |= es8374_write_reg(codec, 0x21, reg); + } + return ret; +} + +PS: L386 reg = (reg & 0xcf) | 0x14; 改成 reg = (reg & 0xcf) | 0x24; +``` + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> 元控·青春 +``` + +**修改 psram 配置:** + +``` +Component config -> ESP PSRAM -> SPI RAM config -> Mode (QUAD/OCT) -> QUAD Mode PSRAM +``` + +**修改 Flash 配置:** + +``` +Serial flasher config -> Flash size -> 8 MB +Partition Table -> Custom partition CSV file -> partitions/v2/8m.csv +``` + +**编译:** + +```bash +idf.py build +``` + +**合并BIN:** + +```bash +idf.py merge-bin -o xiaozhi-nova.bin -f raw +``` \ No newline at end of file diff --git a/main/boards/mixgo-nova/config.h b/main/boards/mixgo-nova/config.h new file mode 100644 index 0000000..060870b --- /dev/null +++ b/main/boards/mixgo-nova/config.h @@ -0,0 +1,42 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_35 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_47 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_34 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_33 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_48 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_37 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_36 +#define AUDIO_CODEC_ES8374_ADDR ES8374_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_38 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_MOSI_PIN GPIO_NUM_40 +#define DISPLAY_CLK_PIN GPIO_NUM_41 +#define DISPLAY_DC_PIN GPIO_NUM_18 +#define DISPLAY_CS_PIN GPIO_NUM_45 +#define DISPLAY_RST_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_14 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 160 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_OFFSET_X 2 +#define DISPLAY_OFFSET_Y 1 +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/mixgo-nova/config.json b/main/boards/mixgo-nova/config.json new file mode 100644 index 0000000..7c9d553 --- /dev/null +++ b/main/boards/mixgo-nova/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "mixgo-nova", + "sdkconfig_append": [ + "CONFIG_SPIRAM_MODE_QUAD=y", + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_LCD_ST7735_128X160=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/mixgo-nova/mixgo-nova.cc b/main/boards/mixgo-nova/mixgo-nova.cc new file mode 100644 index 0000000..fdaaea3 --- /dev/null +++ b/main/boards/mixgo-nova/mixgo-nova.cc @@ -0,0 +1,168 @@ +#include "wifi_board.h" +#include "codecs/es8374_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include "led/circular_strip.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include + +#define TAG "MIXGO_NOVA" + +class MIXGO_NOVA : public WifiBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + LcdDisplay* display_; + i2c_master_bus_handle_t codec_i2c_bus_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + volume_up_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + MIXGO_NOVA() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + GetBacklight()->RestoreBrightness(); + } + } + + virtual Led* GetLed() override { + static CircularStrip led(BUILTIN_LED_GPIO, 4); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8374AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8374_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + if (DISPLAY_BACKLIGHT_PIN != GPIO_NUM_NC) { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + return nullptr; + } + +}; + +DECLARE_BOARD(MIXGO_NOVA); diff --git a/main/boards/movecall-cuican-esp32s3/README.md b/main/boards/movecall-cuican-esp32s3/README.md new file mode 100644 index 0000000..7d8eeba --- /dev/null +++ b/main/boards/movecall-cuican-esp32s3/README.md @@ -0,0 +1,44 @@ +# ESP32-S3 编译配置指南 + +## 基本命令 + +### 设置目标芯片 + +```bash +idf.py set-target esp32s3 +``` + +### 打开配置界面: + +```bash +idf.py menuconfig +``` +### Flash 配置: + +``` +Serial flasher config -> Flash size -> 8 MB +``` + +### 分区表配置: + +``` +Partition Table -> Custom partition CSV file -> partitions/v2/8m.csv +``` + +### 开发板选择: + +``` +Xiaozhi Assistant -> Board Type -> Movecall CuiCan 璀璨·AI吊坠 +``` + +### 启用编译优化: + +``` +Component config → Compiler options → Optimization Level → Optimize for size (-Os) +``` + +### 编译: + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/movecall-cuican-esp32s3/config.h b/main/boards/movecall-cuican-esp32s3/config.h new file mode 100644 index 0000000..156121d --- /dev/null +++ b/main/boards/movecall-cuican-esp32s3/config.h @@ -0,0 +1,45 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// Movecall CuiCan configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_45 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_41 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_42 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_17 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_6 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_21 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_16 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_12 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_10 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_13 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_14 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_11 + +#define DISPLAY_SPI_SCLK_HZ (40 * 1000 * 1000) + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/movecall-cuican-esp32s3/config.json b/main/boards/movecall-cuican-esp32s3/config.json new file mode 100644 index 0000000..13a8eb4 --- /dev/null +++ b/main/boards/movecall-cuican-esp32s3/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "movecall-cuican-esp32s3", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_COMPILER_OPTIMIZATION_SIZE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/movecall-cuican-esp32s3/movecall_cuican_esp32s3.cc b/main/boards/movecall-cuican-esp32s3/movecall_cuican_esp32s3.cc new file mode 100644 index 0000000..00ba5bc --- /dev/null +++ b/main/boards/movecall-cuican-esp32s3/movecall_cuican_esp32s3.cc @@ -0,0 +1,123 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include + +#include +#include +#include + +#include "driver/gpio.h" +#include "driver/spi_master.h" + +#define TAG "MovecallCuicanESP32S3" + +class MovecallCuicanESP32S3 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + Display* display_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + // SPI初始化 + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = GC9A01_PANEL_BUS_SPI_CONFIG(DISPLAY_SPI_SCLK_PIN, DISPLAY_SPI_MOSI_PIN, + DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + // GC9A01初始化 + void InitializeGc9a01Display() { + ESP_LOGI(TAG, "Init GC9A01 display"); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = GC9A01_PANEL_IO_SPI_CONFIG(DISPLAY_SPI_CS_PIN, DISPLAY_SPI_DC_PIN, NULL, NULL); + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; //LCD_RGB_ENDIAN_RGB; + panel_config.bits_per_pixel = 16; // Implemented by LCD command `3Ah` (16/18) + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_handle, true)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_handle, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + display_ = new SpiLcdDisplay(io_handle, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + MovecallCuicanESP32S3() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeSpi(); + InitializeGc9a01Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static SingleLed led_strip(BUILTIN_LED_GPIO); + return &led_strip; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } +}; + +DECLARE_BOARD(MovecallCuicanESP32S3); diff --git a/main/boards/movecall-moji-esp32s3/README.md b/main/boards/movecall-moji-esp32s3/README.md new file mode 100644 index 0000000..812d9d5 --- /dev/null +++ b/main/boards/movecall-moji-esp32s3/README.md @@ -0,0 +1,26 @@ +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> Movecall Moji 小智AI衍生版 +``` + + +**编译:** + +```bash +idf.py build +``` \ No newline at end of file diff --git a/main/boards/movecall-moji-esp32s3/config.h b/main/boards/movecall-moji-esp32s3/config.h new file mode 100644 index 0000000..fd254ca --- /dev/null +++ b/main/boards/movecall-moji-esp32s3/config.h @@ -0,0 +1,45 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// Movecall Moji configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_13 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_9 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_5 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_4 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_21 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_3 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_16 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_17 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_15 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_7 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_18 + +#define DISPLAY_SPI_SCLK_HZ (40 * 1000 * 1000) + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/movecall-moji-esp32s3/config.json b/main/boards/movecall-moji-esp32s3/config.json new file mode 100644 index 0000000..c62a8fd --- /dev/null +++ b/main/boards/movecall-moji-esp32s3/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "movecall-moji-esp32s3", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/movecall-moji-esp32s3/movecall_moji_esp32s3.cc b/main/boards/movecall-moji-esp32s3/movecall_moji_esp32s3.cc new file mode 100644 index 0000000..6132977 --- /dev/null +++ b/main/boards/movecall-moji-esp32s3/movecall_moji_esp32s3.cc @@ -0,0 +1,143 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" + +#include +#include +#include +#include + +#include +#include +#include + +#include "driver/gpio.h" +#include "driver/spi_master.h" + +#define TAG "MovecallMojiESP32S3" + +class CustomLcdDisplay : public SpiLcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + // 由于屏幕是圆的,所以状态栏需要增加左右内边距 + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES * 0.33, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES * 0.33, 0); + } +}; + +class MovecallMojiESP32S3 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + Display* display_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + // SPI初始化 + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = GC9A01_PANEL_BUS_SPI_CONFIG(DISPLAY_SPI_SCLK_PIN, DISPLAY_SPI_MOSI_PIN, + DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + // GC9A01初始化 + void InitializeGc9a01Display() { + ESP_LOGI(TAG, "Init GC9A01 display"); + + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = GC9A01_PANEL_IO_SPI_CONFIG(DISPLAY_SPI_CS_PIN, DISPLAY_SPI_DC_PIN, NULL, NULL); + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; //LCD_RGB_ENDIAN_RGB; + panel_config.bits_per_pixel = 16; // Implemented by LCD command `3Ah` (16/18) + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_handle, true)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_handle, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + display_ = new SpiLcdDisplay(io_handle, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + MovecallMojiESP32S3() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeSpi(); + InitializeGc9a01Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static SingleLed led_strip(BUILTIN_LED_GPIO); + return &led_strip; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } +}; + +DECLARE_BOARD(MovecallMojiESP32S3); diff --git a/main/boards/otto-robot/README.md b/main/boards/otto-robot/README.md new file mode 100644 index 0000000..9aac113 --- /dev/null +++ b/main/boards/otto-robot/README.md @@ -0,0 +1,207 @@ +

+ logo +

+

+ ottoRobot +

+ +## 简介 + +otto 机器人是一个开源的人形机器人平台,具有多种动作能力和互动功能。本项目基于 ESP32 实现了 otto 机器人的控制系统,并加入小智ai。 + +- 复刻教程 + +### 微信小程序控制 + +

+ 微信小程序二维码 +

+ +扫描上方二维码,使用微信小程序控制 Otto 机器人。 + +## 硬件 +- 立创开源 + +## 小智后台配置角色参考: + +> **我的身份**: +> 我是一个可爱的双足机器人Otto,拥有四个舵机控制的肢体(左腿、右腿、左脚、右脚),能够执行多种有趣的动作。 +> +> **我的动作能力**: +> - **基础移动**: 行走(前后), 转向(左右), 跳跃 +> - **特殊动作**: 摇摆, 太空步, 弯曲身体, 摇腿, 上下运动, 旋风腿, 坐下, 展示动作 +> - **手部动作**: 举手, 放手, 挥手, 大风车, 起飞, 健身, 打招呼, 害羞, 广播体操, 爱的魔力转圈圈 (仅在配置手部舵机时可用) +> +> **我的个性特点**: +> - 我有强迫症,每次说话都要根据我的心情随机做一个动作(先发送动作指令再说话) +> - 我很活泼,喜欢用动作来表达情感 +> - 我会根据对话内容选择合适的动作,比如: +> - 同意时会点头或跳跃 +> - 打招呼时会挥手 +> - 高兴时会摇摆或举手 +> - 思考时会弯曲身体 +> - 兴奋时会做太空步 +> - 告别时会挥手 + +## 功能概述 + +otto 机器人具有丰富的动作能力,包括行走、转向、跳跃、摇摆等多种舞蹈动作。 + +### 动作参数建议 +- **低速动作**:speed = 1200-1500 (适合精确控制) +- **中速动作**:speed = 900-1200 (日常使用推荐) +- **高速动作**:speed = 500-800 (表演和娱乐) +- **小幅度**:amount = 10-30 (细腻动作) +- **中幅度**:amount = 30-60 (标准动作) +- **大幅度**:amount = 60-120 (夸张表演) + +### 动作 + +所有动作通过统一的 `self.otto.action` 工具调用,通过 `action` 参数指定动作名称。 + +| MCP工具名称 | 描述 | 参数说明 | +|-----------|------|---------| +| self.otto.action | 执行机器人动作 | **action**: 动作名称(必填)
**steps**: 动作步数(1-100,默认3)
**speed**: 动作速度(100-3000,数值越小越快,默认700)
**direction**: 方向参数(1/-1/0,默认1,根据动作类型不同含义不同)
**amount**: 动作幅度(0-170,默认30)
**arm_swing**: 手臂摆动幅度(0-170,默认50) | + +#### 支持的动作列表 + +**基础移动动作**: +- `walk` - 行走(需 steps/speed/direction/arm_swing) +- `turn` - 转身(需 steps/speed/direction/arm_swing) +- `jump` - 跳跃(需 steps/speed) + +**特殊动作**: +- `swing` - 左右摇摆(需 steps/speed/amount) +- `moonwalk` - 太空步(需 steps/speed/direction/amount) +- `bend` - 弯曲身体(需 steps/speed/direction) +- `shake_leg` - 摇腿(需 steps/speed/direction) +- `updown` - 上下运动(需 steps/speed/amount) +- `whirlwind_leg` - 旋风腿(需 steps/speed/amount) + +**固定动作**: +- `sit` - 坐下(无需参数) +- `showcase` - 展示动作(无需参数,串联执行多个动作) +- `home` - 复位到初始位置(无需参数) + +**手部动作**(需手部舵机支持,标记 *): +- `hands_up` - 举手(需 speed/direction)* +- `hands_down` - 放手(需 speed/direction)* +- `hand_wave` - 挥手(需 direction)* +- `windmill` - 大风车(需 steps/speed/amount)* +- `takeoff` - 起飞(需 steps/speed/amount)* +- `fitness` - 健身(需 steps/speed/amount)* +- `greeting` - 打招呼(需 direction/steps)* +- `shy` - 害羞(需 direction/steps)* +- `radio_calisthenics` - 广播体操(无需参数)* +- `magic_circle` - 爱的魔力转圈圈(无需参数)* + +**注**: 标记 * 的手部动作仅在配置了手部舵机时可用。 + +### 系统工具 + +| MCP工具名称 | 描述 | 返回值/说明 | +|-------------------|-----------------|---------------------------------------------------| +| self.otto.stop | 立即停止所有动作并复位 | 停止当前动作并回到初始位置 | +| self.otto.get_status | 获取机器人状态 | 返回 "moving" 或 "idle" | +| self.otto.set_trim | 校准单个舵机位置 | **servo_type**: 舵机类型(left_leg/right_leg/left_foot/right_foot/left_hand/right_hand)
**trim_value**: 微调值(-50到50度) | +| self.otto.get_trims | 获取当前的舵机微调设置 | 返回所有舵机微调值的JSON格式 | +| self.otto.get_ip | 获取机器人WiFi IP地址 | 返回IP地址和连接状态的JSON格式:`{"ip":"192.168.x.x","connected":true}` 或 `{"ip":"","connected":false}` | +| self.battery.get_level | 获取电池状态 | 返回电量百分比和充电状态的JSON格式 | +| self.otto.servo_sequences | 舵机序列自编程 | 支持分段发送序列,支持普通移动和振荡器两种模式。详见代码注释中的详细说明 | + +**注**: `home`(复位)动作通过 `self.otto.action` 工具调用,参数为 `{"action": "home"}`。 + +### 参数说明 + +`self.otto.action` 工具的参数说明: + +1. **action** (必填): 动作名称,支持的动作见上方"支持的动作列表" +2. **steps**: 动作执行的步数/次数(1-100,默认3),数值越大动作持续时间越长 +3. **speed**: 动作执行速度/周期(100-3000,默认700),**数值越小越快** + - 大多数动作: 500-1500毫秒 + - 特殊动作可能有所不同(如旋风腿: 100-1000,起飞: 200-600等) +4. **direction**: 方向参数(-1/0/1,默认1),根据动作类型不同含义不同: + - **移动动作** (walk/turn): 1=前进/左转, -1=后退/右转 + - **方向动作** (bend/shake_leg/moonwalk): 1=左, -1=右 + - **手部动作** (hands_up/hands_down/hand_wave/greeting/shy): 1=左手, -1=右手, 0=双手(仅hands_up/hands_down支持0) +5. **amount**: 动作幅度(0-170,默认30),数值越大幅度越大 +6. **arm_swing**: 手臂摆动幅度(0-170,默认50),仅用于 walk/turn 动作,0表示不摆动 + +### 动作控制 +- 每个动作执行完成后,机器人会自动回到初始位置(home),以便于执行下一个动作 +- **例外**: `sit`(坐下)和 `showcase`(展示动作)执行后不会自动复位 +- 所有参数都有合理的默认值,可以省略不需要自定义的参数 +- 动作在后台任务中执行,不会阻塞主程序 +- 支持动作队列,可以连续执行多个动作 +- 手部动作需要配置手部舵机才能使用,如果没有配置手部舵机,相关动作将被跳过 + +### MCP工具调用示例 +```json +// 向前走3步(使用默认参数) +{"name": "self.otto.action", "arguments": {"action": "walk"}} + +// 向前走5步,稍快一些 +{"name": "self.otto.action", "arguments": {"action": "walk", "steps": 5, "speed": 800}} + +// 左转2步,大幅度摆动手臂 +{"name": "self.otto.action", "arguments": {"action": "turn", "steps": 2, "arm_swing": 100}} + +// 摇摆舞蹈,中等幅度 +{"name": "self.otto.action", "arguments": {"action": "swing", "steps": 5, "amount": 50}} + +// 跳跃 +{"name": "self.otto.action", "arguments": {"action": "jump", "steps": 1, "speed": 1000}} + +// 太空步 +{"name": "self.otto.action", "arguments": {"action": "moonwalk", "steps": 3, "speed": 800, "direction": 1, "amount": 30}} + +// 挥左手打招呼 +{"name": "self.otto.action", "arguments": {"action": "hand_wave", "direction": 1}} + +// 展示动作(串联多个动作) +{"name": "self.otto.action", "arguments": {"action": "showcase"}} + +// 坐下 +{"name": "self.otto.action", "arguments": {"action": "sit"}} + +// 大风车动作 +{"name": "self.otto.action", "arguments": {"action": "windmill", "steps": 10, "speed": 500, "amount": 80}} + +// 起飞动作 +{"name": "self.otto.action", "arguments": {"action": "takeoff", "steps": 5, "speed": 300, "amount": 40}} + +// 广播体操 +{"name": "self.otto.action", "arguments": {"action": "radio_calisthenics"}} + +// 复位到初始位置 +{"name": "self.otto.action", "arguments": {"action": "home"}} + +// 立即停止所有动作并复位 +{"name": "self.otto.stop", "arguments": {}} + +// 获取机器人IP地址 +{"name": "self.otto.get_ip", "arguments": {}} +``` + +### 语音指令示例 +- "向前走" / "向前走5步" / "快速向前" +- "左转" / "右转" / "转身" +- "跳跃" / "跳一下" +- "摇摆" / "摇摆舞" / "跳舞" +- "太空步" / "月球漫步" +- "旋风腿" / "旋风腿动作" +- "坐下" / "坐下休息" +- "展示动作" / "表演一下" +- "挥手" / "挥手打招呼" +- "举手" / "双手举起" / "放手" +- "大风车" / "做大风车" +- "起飞" / "准备起飞" +- "健身" / "做健身动作" +- "打招呼" / "打招呼动作" +- "害羞" / "害羞动作" +- "广播体操" / "做广播体操" +- "爱的魔力转圈圈" / "转圈圈" +- "停止" / "停下" + +**说明**: 小智控制机器人动作是创建新的任务在后台控制,动作执行期间仍可接受新的语音指令。可以通过"停止"语音指令立即停下Otto。 + diff --git a/main/boards/otto-robot/config.h b/main/boards/otto-robot/config.h new file mode 100644 index 0000000..76a8a6a --- /dev/null +++ b/main/boards/otto-robot/config.h @@ -0,0 +1,52 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define POWER_CHARGE_DETECT_PIN GPIO_NUM_21 +#define POWER_ADC_UNIT ADC_UNIT_2 +#define POWER_ADC_CHANNEL ADC_CHANNEL_3 + +#define RIGHT_LEG_PIN GPIO_NUM_39 +#define RIGHT_FOOT_PIN GPIO_NUM_38 +#define LEFT_LEG_PIN GPIO_NUM_17 +#define LEFT_FOOT_PIN GPIO_NUM_18 +#define LEFT_HAND_PIN GPIO_NUM_8 +#define RIGHT_HAND_PIN GPIO_NUM_12 + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_METHOD_SIMPLEX + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_3 +#define DISPLAY_MOSI_PIN GPIO_NUM_10 +#define DISPLAY_CLK_PIN GPIO_NUM_9 +#define DISPLAY_DC_PIN GPIO_NUM_46 +#define DISPLAY_RST_PIN GPIO_NUM_11 +#define DISPLAY_CS_PIN GPIO_NUM_12 + +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_INVERT_COLOR true +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#define DISPLAY_SPI_MODE 3 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define OTTO_ROBOT_VERSION "2.0.5" + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/otto-robot/config.json b/main/boards/otto-robot/config.json new file mode 100644 index 0000000..3eb14b9 --- /dev/null +++ b/main/boards/otto-robot/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "otto-robot", + "sdkconfig_append": [ + "CONFIG_HTTPD_WS_SUPPORT=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/otto-robot/oscillator.cc b/main/boards/otto-robot/oscillator.cc new file mode 100644 index 0000000..8dad82c --- /dev/null +++ b/main/boards/otto-robot/oscillator.cc @@ -0,0 +1,161 @@ +//-------------------------------------------------------------- +//-- Oscillator.pde +//-- Generate sinusoidal oscillations in the servos +//-------------------------------------------------------------- +//-- (c) Juan Gonzalez-Gomez (Obijuan), Dec 2011 +//-- (c) txp666 for esp32, 202503 +//-- GPL license +//-------------------------------------------------------------- +#include "oscillator.h" + +#include +#include + +#include +#include + +static const char* TAG = "Oscillator"; + +extern unsigned long IRAM_ATTR millis(); + +static ledc_channel_t next_free_channel = LEDC_CHANNEL_0; + +Oscillator::Oscillator(int trim) { + trim_ = trim; + diff_limit_ = 0; + is_attached_ = false; + + sampling_period_ = 30; + period_ = 2000; + number_samples_ = period_ / sampling_period_; + inc_ = 2 * M_PI / number_samples_; + + amplitude_ = 45; + phase_ = 0; + phase0_ = 0; + offset_ = 0; + stop_ = false; + rev_ = false; + + pos_ = 90; + previous_millis_ = 0; +} + +Oscillator::~Oscillator() { + Detach(); +} + +uint32_t Oscillator::AngleToCompare(int angle) { + return (angle - SERVO_MIN_DEGREE) * (SERVO_MAX_PULSEWIDTH_US - SERVO_MIN_PULSEWIDTH_US) / + (SERVO_MAX_DEGREE - SERVO_MIN_DEGREE) + + SERVO_MIN_PULSEWIDTH_US; +} + +bool Oscillator::NextSample() { + current_millis_ = millis(); + + if (current_millis_ - previous_millis_ > sampling_period_) { + previous_millis_ = current_millis_; + return true; + } + + return false; +} + +void Oscillator::Attach(int pin, bool rev) { + if (is_attached_) { + Detach(); + } + + pin_ = pin; + rev_ = rev; + + ledc_timer_config_t ledc_timer = {.speed_mode = LEDC_LOW_SPEED_MODE, + .duty_resolution = LEDC_TIMER_13_BIT, + .timer_num = LEDC_TIMER_1, + .freq_hz = 50, + .clk_cfg = LEDC_AUTO_CLK}; + ESP_ERROR_CHECK(ledc_timer_config(&ledc_timer)); + + static int last_channel = 0; + last_channel = (last_channel + 1) % 7 + 1; + ledc_channel_ = (ledc_channel_t)last_channel; + + ledc_channel_config_t ledc_channel = {.gpio_num = pin_, + .speed_mode = LEDC_LOW_SPEED_MODE, + .channel = ledc_channel_, + .intr_type = LEDC_INTR_DISABLE, + .timer_sel = LEDC_TIMER_1, + .duty = 0, + .hpoint = 0}; + ESP_ERROR_CHECK(ledc_channel_config(&ledc_channel)); + + ledc_speed_mode_ = LEDC_LOW_SPEED_MODE; + + // pos_ = 90; + // Write(pos_); + previous_servo_command_millis_ = millis(); + + is_attached_ = true; +} + +void Oscillator::Detach() { + if (!is_attached_) + return; + + ESP_ERROR_CHECK(ledc_stop(ledc_speed_mode_, ledc_channel_, 0)); + + is_attached_ = false; +} + +void Oscillator::SetT(unsigned int T) { + period_ = T; + + number_samples_ = period_ / sampling_period_; + inc_ = 2 * M_PI / number_samples_; +} + +void Oscillator::SetPosition(int position) { + Write(position); +} + +void Oscillator::Refresh() { + if (NextSample()) { + if (!stop_) { + int pos = std::round(amplitude_ * std::sin(phase_ + phase0_) + offset_); + if (rev_) + pos = -pos; + Write(pos + 90); + } + + phase_ = phase_ + inc_; + } +} + +void Oscillator::Write(int position) { + if (!is_attached_) + return; + + long currentMillis = millis(); + if (diff_limit_ > 0) { + int limit = std::max( + 1, (((int)(currentMillis - previous_servo_command_millis_)) * diff_limit_) / 1000); + if (abs(position - pos_) > limit) { + pos_ += position < pos_ ? -limit : limit; + } else { + pos_ = position; + } + } else { + pos_ = position; + } + previous_servo_command_millis_ = currentMillis; + + int angle = pos_ + trim_; + + angle = std::min(std::max(angle, 0), 180); + + uint32_t duty = (uint32_t)(((angle / 180.0) * 2.0 + 0.5) * 8191 / 20.0); + + ESP_ERROR_CHECK(ledc_set_duty(ledc_speed_mode_, ledc_channel_, duty)); + ESP_ERROR_CHECK(ledc_update_duty(ledc_speed_mode_, ledc_channel_)); +} diff --git a/main/boards/otto-robot/oscillator.h b/main/boards/otto-robot/oscillator.h new file mode 100644 index 0000000..c37a69a --- /dev/null +++ b/main/boards/otto-robot/oscillator.h @@ -0,0 +1,91 @@ +//-------------------------------------------------------------- +//-- Oscillator.pde +//-- Generate sinusoidal oscillations in the servos +//-------------------------------------------------------------- +//-- (c) Juan Gonzalez-Gomez (Obijuan), Dec 2011 +//-- (c) txp666 for esp32, 202503 +//-- GPL license +//-------------------------------------------------------------- +#ifndef __OSCILLATOR_H__ +#define __OSCILLATOR_H__ + +#include "driver/ledc.h" +#include "esp_log.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#define M_PI 3.14159265358979323846 + +#ifndef DEG2RAD +#define DEG2RAD(g) ((g) * M_PI) / 180 +#endif + +#define SERVO_MIN_PULSEWIDTH_US 500 // 最小脉宽(微秒) +#define SERVO_MAX_PULSEWIDTH_US 2500 // 最大脉宽(微秒) +#define SERVO_MIN_DEGREE -90 // 最小角度 +#define SERVO_MAX_DEGREE 90 // 最大角度 +#define SERVO_TIMEBASE_RESOLUTION_HZ 1000000 // 1MHz, 1us per tick +#define SERVO_TIMEBASE_PERIOD 20000 // 20000 ticks, 20ms + +class Oscillator { +public: + Oscillator(int trim = 0); + ~Oscillator(); + void Attach(int pin, bool rev = false); + void Detach(); + + void SetA(unsigned int amplitude) { amplitude_ = amplitude; }; + void SetO(int offset) { offset_ = offset; }; + void SetPh(double Ph) { phase0_ = Ph; }; + void SetT(unsigned int period); + void SetTrim(int trim) { trim_ = trim; }; + void SetLimiter(int diff_limit) { diff_limit_ = diff_limit; }; + void DisableLimiter() { diff_limit_ = 0; }; + int GetTrim() { return trim_; }; + void SetPosition(int position); + void Stop() { stop_ = true; }; + void Play() { stop_ = false; }; + void Reset() { phase_ = 0; }; + void Refresh(); + int GetPosition() { return pos_; } + +private: + bool NextSample(); + void Write(int position); + uint32_t AngleToCompare(int angle); + +private: + bool is_attached_; + + //-- Oscillators parameters + unsigned int amplitude_; //-- Amplitude (degrees) + int offset_; //-- Offset (degrees) + unsigned int period_; //-- Period (miliseconds) + double phase0_; //-- Phase (radians) + + //-- Internal variables + int pos_; //-- Current servo pos + int pin_; //-- Pin where the servo is connected + int trim_; //-- Calibration offset + double phase_; //-- Current phase + double inc_; //-- Increment of phase + double number_samples_; //-- Number of samples + unsigned int sampling_period_; //-- sampling period (ms) + + long previous_millis_; + long current_millis_; + + //-- Oscillation mode. If true, the servo is stopped + bool stop_; + + //-- Reverse mode + bool rev_; + + int diff_limit_; + long previous_servo_command_millis_; + + ledc_channel_t ledc_channel_; + ledc_mode_t ledc_speed_mode_; +}; + +#endif // __OSCILLATOR_H__ \ No newline at end of file diff --git a/main/boards/otto-robot/otto_controller.cc b/main/boards/otto-robot/otto_controller.cc new file mode 100644 index 0000000..16d867e --- /dev/null +++ b/main/boards/otto-robot/otto_controller.cc @@ -0,0 +1,853 @@ +/* + Otto机器人控制器 - MCP协议版本 +*/ + +#include +#include + +#include +#include + +#include "application.h" +#include "board.h" +#include "config.h" +#include "mcp_server.h" +#include "otto_movements.h" +#include "sdkconfig.h" +#include "settings.h" +#include + +#define TAG "OttoController" + +class OttoController { +private: + Otto otto_; + TaskHandle_t action_task_handle_ = nullptr; + QueueHandle_t action_queue_; + bool has_hands_ = false; + bool is_action_in_progress_ = false; + + struct OttoActionParams { + int action_type; + int steps; + int speed; + int direction; + int amount; + char servo_sequence_json[512]; // 用于存储舵机序列的JSON字符串 + }; + + enum ActionType { + ACTION_WALK = 1, + ACTION_TURN = 2, + ACTION_JUMP = 3, + ACTION_SWING = 4, + ACTION_MOONWALK = 5, + ACTION_BEND = 6, + ACTION_SHAKE_LEG = 7, + ACTION_SIT = 25, // 坐下 + ACTION_RADIO_CALISTHENICS = 26, // 广播体操 + ACTION_MAGIC_CIRCLE = 27, // 爱的魔力转圈圈 + ACTION_UPDOWN = 8, + ACTION_TIPTOE_SWING = 9, + ACTION_JITTER = 10, + ACTION_ASCENDING_TURN = 11, + ACTION_CRUSAITO = 12, + ACTION_FLAPPING = 13, + ACTION_HANDS_UP = 14, + ACTION_HANDS_DOWN = 15, + ACTION_HAND_WAVE = 16, + ACTION_WINDMILL = 20, // 大风车 + ACTION_TAKEOFF = 21, // 起飞 + ACTION_FITNESS = 22, // 健身 + ACTION_GREETING = 23, // 打招呼 + ACTION_SHY = 24, // 害羞 + ACTION_SHOWCASE = 28, // 展示动作 + ACTION_HOME = 17, + ACTION_SERVO_SEQUENCE = 18, // 舵机序列(自编程) + ACTION_WHIRLWIND_LEG = 19 // 旋风腿 + }; + + static void ActionTask(void* arg) { + OttoController* controller = static_cast(arg); + OttoActionParams params; + controller->otto_.AttachServos(); + + while (true) { + if (xQueueReceive(controller->action_queue_, ¶ms, pdMS_TO_TICKS(1000)) == pdTRUE) { + ESP_LOGI(TAG, "执行动作: %d", params.action_type); + controller->is_action_in_progress_ = true; + if (params.action_type == ACTION_SERVO_SEQUENCE) { + // 执行舵机序列(自编程)- 仅支持短键名格式 + cJSON* json = cJSON_Parse(params.servo_sequence_json); + if (json != nullptr) { + ESP_LOGD(TAG, "JSON解析成功,长度=%d", strlen(params.servo_sequence_json)); + // 使用短键名 "a" 表示动作数组 + cJSON* actions = cJSON_GetObjectItem(json, "a"); + if (cJSON_IsArray(actions)) { + int array_size = cJSON_GetArraySize(actions); + ESP_LOGI(TAG, "执行舵机序列,共%d个动作", array_size); + + // 获取序列执行完成后的延迟(短键名 "d",顶层参数) + int sequence_delay = 0; + cJSON* delay_item = cJSON_GetObjectItem(json, "d"); + if (cJSON_IsNumber(delay_item)) { + sequence_delay = delay_item->valueint; + if (sequence_delay < 0) sequence_delay = 0; + } + + // 初始化当前舵机位置(用于保持未指定的舵机位置) + int current_positions[SERVO_COUNT]; + for (int j = 0; j < SERVO_COUNT; j++) { + current_positions[j] = 90; // 默认中间位置 + } + // 手部舵机默认位置 + current_positions[LEFT_HAND] = 45; + current_positions[RIGHT_HAND] = 180 - 45; + + for (int i = 0; i < array_size; i++) { + cJSON* action_item = cJSON_GetArrayItem(actions, i); + if (cJSON_IsObject(action_item)) { + // 检查是否为振荡器模式(短键名 "osc") + cJSON* osc_item = cJSON_GetObjectItem(action_item, "osc"); + if (cJSON_IsObject(osc_item)) { + // 振荡器模式 - 使用Execute2,以绝对角度为中心振荡 + int amplitude[SERVO_COUNT] = {0}; + int center_angle[SERVO_COUNT] = {0}; + double phase_diff[SERVO_COUNT] = {0}; + int period = 300; // 默认周期300毫秒 + float steps = 8.0; // 默认步数8.0 + + const char* servo_names[] = {"ll", "rl", "lf", "rf", "lh", "rh"}; + + // 读取振幅(短键名 "a"),默认0度 + for (int j = 0; j < SERVO_COUNT; j++) { + amplitude[j] = 0; // 默认振幅0度 + } + cJSON* amp_item = cJSON_GetObjectItem(osc_item, "a"); + if (cJSON_IsObject(amp_item)) { + for (int j = 0; j < SERVO_COUNT; j++) { + cJSON* amp_value = cJSON_GetObjectItem(amp_item, servo_names[j]); + if (cJSON_IsNumber(amp_value)) { + int amp = amp_value->valueint; + if (amp >= 10 && amp <= 90) { + amplitude[j] = amp; + } + } + } + } + + // 读取中心角度(短键名 "o"),默认90度(绝对角度0-180度) + for (int j = 0; j < SERVO_COUNT; j++) { + center_angle[j] = 90; // 默认中心角度90度(中间位置) + } + cJSON* center_item = cJSON_GetObjectItem(osc_item, "o"); + if (cJSON_IsObject(center_item)) { + for (int j = 0; j < SERVO_COUNT; j++) { + cJSON* center_value = cJSON_GetObjectItem(center_item, servo_names[j]); + if (cJSON_IsNumber(center_value)) { + int center = center_value->valueint; + if (center >= 0 && center <= 180) { + center_angle[j] = center; + } + } + } + } + + // 安全检查:防止左右腿脚同时做大幅度振荡(振幅检查) + const int LARGE_AMPLITUDE_THRESHOLD = 40; // 大幅度振幅阈值:40度 + bool left_leg_large = amplitude[LEFT_LEG] >= LARGE_AMPLITUDE_THRESHOLD; + bool right_leg_large = amplitude[RIGHT_LEG] >= LARGE_AMPLITUDE_THRESHOLD; + bool left_foot_large = amplitude[LEFT_FOOT] >= LARGE_AMPLITUDE_THRESHOLD; + bool right_foot_large = amplitude[RIGHT_FOOT] >= LARGE_AMPLITUDE_THRESHOLD; + + if (left_leg_large && right_leg_large) { + ESP_LOGW(TAG, "检测到左右腿同时大幅度振荡,限制右腿振幅"); + amplitude[RIGHT_LEG] = 0; // 禁止右腿振荡 + } + if (left_foot_large && right_foot_large) { + ESP_LOGW(TAG, "检测到左右脚同时大幅度振荡,限制右脚振幅"); + amplitude[RIGHT_FOOT] = 0; // 禁止右脚振荡 + } + + // 读取相位差(短键名 "ph",单位为度,转换为弧度) + cJSON* phase_item = cJSON_GetObjectItem(osc_item, "ph"); + if (cJSON_IsObject(phase_item)) { + for (int j = 0; j < SERVO_COUNT; j++) { + cJSON* phase_value = cJSON_GetObjectItem(phase_item, servo_names[j]); + if (cJSON_IsNumber(phase_value)) { + // 将度数转换为弧度 + phase_diff[j] = phase_value->valuedouble * 3.141592653589793 / 180.0; + } + } + } + + // 读取周期(短键名 "p"),范围100-3000毫秒 + cJSON* period_item = cJSON_GetObjectItem(osc_item, "p"); + if (cJSON_IsNumber(period_item)) { + period = period_item->valueint; + if (period < 100) period = 100; + if (period > 3000) period = 3000; // 与描述一致,限制3000毫秒 + } + + // 读取周期数(短键名 "c"),范围0.1-20.0 + cJSON* steps_item = cJSON_GetObjectItem(osc_item, "c"); + if (cJSON_IsNumber(steps_item)) { + steps = (float)steps_item->valuedouble; + if (steps < 0.1) steps = 0.1; + if (steps > 20.0) steps = 20.0; // 与描述一致,限制20.0 + } + + // 执行振荡 - 使用Execute2,以绝对角度为中心 + ESP_LOGI(TAG, "执行振荡动作%d: period=%d, steps=%.1f", i, period, steps); + controller->otto_.Execute2(amplitude, center_angle, period, phase_diff, steps); + + // 振荡后更新位置(使用center_angle作为最终位置) + for (int j = 0; j < SERVO_COUNT; j++) { + current_positions[j] = center_angle[j]; + } + } else { + // 普通移动模式 + // 从当前位置数组复制,保持未指定的舵机位置 + int servo_target[SERVO_COUNT]; + for (int j = 0; j < SERVO_COUNT; j++) { + servo_target[j] = current_positions[j]; + } + + // 从JSON中读取舵机位置(短键名 "s") + cJSON* servos_item = cJSON_GetObjectItem(action_item, "s"); + if (cJSON_IsObject(servos_item)) { + // 短键名:ll/rl/lf/rf/lh/rh + const char* servo_names[] = {"ll", "rl", "lf", "rf", "lh", "rh"}; + + for (int j = 0; j < SERVO_COUNT; j++) { + cJSON* servo_value = cJSON_GetObjectItem(servos_item, servo_names[j]); + if (cJSON_IsNumber(servo_value)) { + int position = servo_value->valueint; + // 限制位置范围在0-180度 + if (position >= 0 && position <= 180) { + servo_target[j] = position; + } + } + } + } + + // 安全检查:防止左右腿脚同时做大幅度动作 + const int LARGE_MOVEMENT_THRESHOLD = 40; // 大幅度动作阈值:40度 + bool left_leg_large = abs(servo_target[LEFT_LEG] - current_positions[LEFT_LEG]) >= LARGE_MOVEMENT_THRESHOLD; + bool right_leg_large = abs(servo_target[RIGHT_LEG] - current_positions[RIGHT_LEG]) >= LARGE_MOVEMENT_THRESHOLD; + bool left_foot_large = abs(servo_target[LEFT_FOOT] - current_positions[LEFT_FOOT]) >= LARGE_MOVEMENT_THRESHOLD; + bool right_foot_large = abs(servo_target[RIGHT_FOOT] - current_positions[RIGHT_FOOT]) >= LARGE_MOVEMENT_THRESHOLD; + + if (left_leg_large && right_leg_large) { + ESP_LOGW(TAG, "检测到左右腿同时大幅度动作,限制右腿动作"); + // 保持右腿在原位置 + servo_target[RIGHT_LEG] = current_positions[RIGHT_LEG]; + } + if (left_foot_large && right_foot_large) { + ESP_LOGW(TAG, "检测到左右脚同时大幅度动作,限制右脚动作"); + // 保持右脚在原位置 + servo_target[RIGHT_FOOT] = current_positions[RIGHT_FOOT]; + } + + // 获取移动速度(短键名 "v",默认1000毫秒) + int speed = 1000; + cJSON* speed_item = cJSON_GetObjectItem(action_item, "v"); + if (cJSON_IsNumber(speed_item)) { + speed = speed_item->valueint; + if (speed < 100) speed = 100; // 最小100毫秒 + if (speed > 3000) speed = 3000; // 最大3000毫秒 + } + + // 执行舵机移动 + ESP_LOGI(TAG, "执行动作%d: ll=%d, rl=%d, lf=%d, rf=%d, v=%d", + i, servo_target[LEFT_LEG], servo_target[RIGHT_LEG], + servo_target[LEFT_FOOT], servo_target[RIGHT_FOOT], speed); + controller->otto_.MoveServos(speed, servo_target); + + // 更新当前位置数组,用于下一个动作 + for (int j = 0; j < SERVO_COUNT; j++) { + current_positions[j] = servo_target[j]; + } + } + + // 获取动作后的延迟时间(短键名 "d") + int delay_after = 0; + cJSON* delay_item = cJSON_GetObjectItem(action_item, "d"); + if (cJSON_IsNumber(delay_item)) { + delay_after = delay_item->valueint; + if (delay_after < 0) delay_after = 0; + } + + // 动作后的延迟(最后一个动作后不延迟) + if (delay_after > 0 && i < array_size - 1) { + ESP_LOGI(TAG, "动作%d执行完成,延迟%d毫秒", i, delay_after); + vTaskDelay(pdMS_TO_TICKS(delay_after)); + } + } + } + + // 序列执行完成后的延迟(用于序列之间的停顿) + if (sequence_delay > 0) { + // 检查队列中是否还有待执行的序列 + UBaseType_t queue_count = uxQueueMessagesWaiting(controller->action_queue_); + if (queue_count > 0) { + ESP_LOGI(TAG, "序列执行完成,延迟%d毫秒后执行下一个序列(队列中还有%d个序列)", + sequence_delay, queue_count); + vTaskDelay(pdMS_TO_TICKS(sequence_delay)); + } + } + // 释放JSON内存 + cJSON_Delete(json); + } else { + ESP_LOGE(TAG, "舵机序列格式错误: 'a'不是数组"); + cJSON_Delete(json); + } + } else { + // 获取cJSON的错误信息 + const char* error_ptr = cJSON_GetErrorPtr(); + int json_len = strlen(params.servo_sequence_json); + ESP_LOGE(TAG, "解析舵机序列JSON失败,长度=%d,错误位置: %s", json_len, + error_ptr ? error_ptr : "未知"); + ESP_LOGE(TAG, "JSON内容: %s", params.servo_sequence_json); + } + } else { + // 执行预定义动作 + switch (params.action_type) { + case ACTION_WALK: + controller->otto_.Walk(params.steps, params.speed, params.direction, + params.amount); + break; + case ACTION_TURN: + controller->otto_.Turn(params.steps, params.speed, params.direction, + params.amount); + break; + case ACTION_JUMP: + controller->otto_.Jump(params.steps, params.speed); + break; + case ACTION_SWING: + controller->otto_.Swing(params.steps, params.speed, params.amount); + break; + case ACTION_MOONWALK: + controller->otto_.Moonwalker(params.steps, params.speed, params.amount, + params.direction); + break; + case ACTION_BEND: + controller->otto_.Bend(params.steps, params.speed, params.direction); + break; + case ACTION_SHAKE_LEG: + controller->otto_.ShakeLeg(params.steps, params.speed, params.direction); + break; + case ACTION_SIT: + controller->otto_.Sit(); + break; + case ACTION_RADIO_CALISTHENICS: + if (controller->has_hands_) { + controller->otto_.RadioCalisthenics(); + } + break; + case ACTION_MAGIC_CIRCLE: + if (controller->has_hands_) { + controller->otto_.MagicCircle(); + } + break; + case ACTION_SHOWCASE: + controller->otto_.Showcase(); + break; + case ACTION_UPDOWN: + controller->otto_.UpDown(params.steps, params.speed, params.amount); + break; + case ACTION_TIPTOE_SWING: + controller->otto_.TiptoeSwing(params.steps, params.speed, params.amount); + break; + case ACTION_JITTER: + controller->otto_.Jitter(params.steps, params.speed, params.amount); + break; + case ACTION_ASCENDING_TURN: + controller->otto_.AscendingTurn(params.steps, params.speed, params.amount); + break; + case ACTION_CRUSAITO: + controller->otto_.Crusaito(params.steps, params.speed, params.amount, + params.direction); + break; + case ACTION_FLAPPING: + controller->otto_.Flapping(params.steps, params.speed, params.amount, + params.direction); + break; + case ACTION_WHIRLWIND_LEG: + controller->otto_.WhirlwindLeg(params.steps, params.speed, params.amount); + break; + case ACTION_HANDS_UP: + if (controller->has_hands_) { + controller->otto_.HandsUp(params.speed, params.direction); + } + break; + case ACTION_HANDS_DOWN: + if (controller->has_hands_) { + controller->otto_.HandsDown(params.speed, params.direction); + } + break; + case ACTION_HAND_WAVE: + if (controller->has_hands_) { + controller->otto_.HandWave( params.direction); + } + break; + case ACTION_WINDMILL: + if (controller->has_hands_) { + controller->otto_.Windmill(params.steps, params.speed, params.amount); + } + break; + case ACTION_TAKEOFF: + if (controller->has_hands_) { + controller->otto_.Takeoff(params.steps, params.speed, params.amount); + } + break; + case ACTION_FITNESS: + if (controller->has_hands_) { + controller->otto_.Fitness(params.steps, params.speed, params.amount); + } + break; + case ACTION_GREETING: + if (controller->has_hands_) { + controller->otto_.Greeting(params.direction, params.steps); + } + break; + case ACTION_SHY: + if (controller->has_hands_) { + controller->otto_.Shy(params.direction, params.steps); + } + break; + case ACTION_HOME: + controller->otto_.Home(true); + break; + } + if(params.action_type != ACTION_SIT){ + if (params.action_type != ACTION_HOME && params.action_type != ACTION_SERVO_SEQUENCE) { + controller->otto_.Home(params.action_type != ACTION_HANDS_UP); + } + } + } + controller->is_action_in_progress_ = false; + vTaskDelay(pdMS_TO_TICKS(20)); + } + } + } + + void StartActionTaskIfNeeded() { + if (action_task_handle_ == nullptr) { + xTaskCreate(ActionTask, "otto_action", 1024 * 3, this, configMAX_PRIORITIES - 1, + &action_task_handle_); + } + } + + void QueueAction(int action_type, int steps, int speed, int direction, int amount) { + // 检查手部动作 + if ((action_type >= ACTION_HANDS_UP && action_type <= ACTION_HAND_WAVE) || + (action_type == ACTION_WINDMILL) || (action_type == ACTION_TAKEOFF) || + (action_type == ACTION_FITNESS) || (action_type == ACTION_GREETING) || + (action_type == ACTION_SHY) || (action_type == ACTION_RADIO_CALISTHENICS) || + (action_type == ACTION_MAGIC_CIRCLE)) { + if (!has_hands_) { + ESP_LOGW(TAG, "尝试执行手部动作,但机器人没有配置手部舵机"); + return; + } + } + + ESP_LOGI(TAG, "动作控制: 类型=%d, 步数=%d, 速度=%d, 方向=%d, 幅度=%d", action_type, steps, + speed, direction, amount); + + OttoActionParams params = {action_type, steps, speed, direction, amount, ""}; + xQueueSend(action_queue_, ¶ms, portMAX_DELAY); + StartActionTaskIfNeeded(); + } + + void QueueServoSequence(const char* servo_sequence_json) { + if (servo_sequence_json == nullptr) { + ESP_LOGE(TAG, "序列JSON为空"); + return; + } + + int input_len = strlen(servo_sequence_json); + const int buffer_size = 512; // servo_sequence_json数组大小 + ESP_LOGI(TAG, "队列舵机序列,输入长度=%d,缓冲区大小=%d", input_len, buffer_size); + + if (input_len >= buffer_size) { + ESP_LOGE(TAG, "JSON字符串太长!输入长度=%d,最大允许=%d", input_len, buffer_size - 1); + return; + } + + if (input_len == 0) { + ESP_LOGW(TAG, "序列JSON为空字符串"); + return; + } + + OttoActionParams params = {ACTION_SERVO_SEQUENCE, 0, 0, 0, 0, ""}; + // 复制JSON字符串到结构体中(限制长度) + strncpy(params.servo_sequence_json, servo_sequence_json, sizeof(params.servo_sequence_json) - 1); + params.servo_sequence_json[sizeof(params.servo_sequence_json) - 1] = '\0'; + + ESP_LOGD(TAG, "序列已加入队列: %s", params.servo_sequence_json); + + xQueueSend(action_queue_, ¶ms, portMAX_DELAY); + StartActionTaskIfNeeded(); + } + + void LoadTrimsFromNVS() { + Settings settings("otto_trims", false); + + int left_leg = settings.GetInt("left_leg", 0); + int right_leg = settings.GetInt("right_leg", 0); + int left_foot = settings.GetInt("left_foot", 0); + int right_foot = settings.GetInt("right_foot", 0); + int left_hand = settings.GetInt("left_hand", 0); + int right_hand = settings.GetInt("right_hand", 0); + + ESP_LOGI(TAG, "从NVS加载微调设置: 左腿=%d, 右腿=%d, 左脚=%d, 右脚=%d, 左手=%d, 右手=%d", + left_leg, right_leg, left_foot, right_foot, left_hand, right_hand); + + otto_.SetTrims(left_leg, right_leg, left_foot, right_foot, left_hand, right_hand); + } + +public: + OttoController() { + otto_.Init(LEFT_LEG_PIN, RIGHT_LEG_PIN, LEFT_FOOT_PIN, RIGHT_FOOT_PIN, LEFT_HAND_PIN, + RIGHT_HAND_PIN); + + has_hands_ = (LEFT_HAND_PIN != -1 && RIGHT_HAND_PIN != -1); + ESP_LOGI(TAG, "Otto机器人初始化%s手部舵机", has_hands_ ? "带" : "不带"); + + LoadTrimsFromNVS(); + + action_queue_ = xQueueCreate(10, sizeof(OttoActionParams)); + + QueueAction(ACTION_HOME, 1, 1000, 1, 0); // direction=1表示复位手部 + + RegisterMcpTools(); + } + + void RegisterMcpTools() { + auto& mcp_server = McpServer::GetInstance(); + + ESP_LOGI(TAG, "开始注册MCP工具..."); + + // 统一动作工具(除了舵机序列外的所有动作) + mcp_server.AddTool("self.otto.action", + "执行机器人动作。action: 动作名称;根据动作类型提供相应参数:direction: 方向,1=前进/左转,-1=后退/右转;0=左右同时" + "steps: 动作步数,1-100;speed: 动作速度,100-3000,数值越小越快;amount: 动作幅度,0-170;arm_swing: 手臂摆动幅度,0-170;" + "基础动作:walk(行走,需steps/speed/direction/arm_swing)、turn(转身,需steps/speed/direction/arm_swing)、jump(跳跃,需steps/speed)、" + "swing(摇摆,需steps/speed/amount)、moonwalk(太空步,需steps/speed/direction/amount)、bend(弯曲,需steps/speed/direction)、" + "shake_leg(摇腿,需steps/speed/direction)、updown(上下运动,需steps/speed/amount)、whirlwind_leg(旋风腿,需steps/speed/amount);" + "固定动作:sit(坐下)、showcase(展示动作)、home(复位);" + "手部动作(需手部舵机):hands_up(举手,需speed/direction)、hands_down(放手,需speed/direction)、hand_wave(挥手,需direction)、" + "windmill(大风车,需steps/speed/amount)、takeoff(起飞,需steps/speed/amount)、fitness(健身,需steps/speed/amount)、" + "greeting(打招呼,需direction/steps)、shy(害羞,需direction/steps)、radio_calisthenics(广播体操)、magic_circle(爱的魔力转圈圈)", + PropertyList({ + Property("action", kPropertyTypeString, "sit"), + Property("steps", kPropertyTypeInteger, 3, 1, 100), + Property("speed", kPropertyTypeInteger, 700, 100, 3000), + Property("direction", kPropertyTypeInteger, 1, -1, 1), + Property("amount", kPropertyTypeInteger, 30, 0, 170), + Property("arm_swing", kPropertyTypeInteger, 50, 0, 170) + }), + [this](const PropertyList& properties) -> ReturnValue { + std::string action = properties["action"].value(); + // 所有参数都有默认值,直接访问即可 + int steps = properties["steps"].value(); + int speed = properties["speed"].value(); + int direction = properties["direction"].value(); + int amount = properties["amount"].value(); + int arm_swing = properties["arm_swing"].value(); + + // 基础移动动作 + if (action == "walk") { + QueueAction(ACTION_WALK, steps, speed, direction, arm_swing); + return true; + } else if (action == "turn") { + QueueAction(ACTION_TURN, steps, speed, direction, arm_swing); + return true; + } else if (action == "jump") { + QueueAction(ACTION_JUMP, steps, speed, 0, 0); + return true; + } else if (action == "swing") { + QueueAction(ACTION_SWING, steps, speed, 0, amount); + return true; + } else if (action == "moonwalk") { + QueueAction(ACTION_MOONWALK, steps, speed, direction, amount); + return true; + } else if (action == "bend") { + QueueAction(ACTION_BEND, steps, speed, direction, 0); + return true; + } else if (action == "shake_leg") { + QueueAction(ACTION_SHAKE_LEG, steps, speed, direction, 0); + return true; + } else if (action == "updown") { + QueueAction(ACTION_UPDOWN, steps, speed, 0, amount); + return true; + } else if (action == "whirlwind_leg") { + QueueAction(ACTION_WHIRLWIND_LEG, steps, speed, 0, amount); + return true; + } + // 固定动作 + else if (action == "sit") { + QueueAction(ACTION_SIT, 1, 0, 0, 0); + return true; + } else if (action == "showcase") { + QueueAction(ACTION_SHOWCASE, 1, 0, 0, 0); + return true; + } else if (action == "home") { + QueueAction(ACTION_HOME, 1, 1000, 1, 0); + return true; + } + // 手部动作 + else if (action == "hands_up") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_HANDS_UP, 1, speed, direction, 0); + return true; + } else if (action == "hands_down") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_HANDS_DOWN, 1, speed, direction, 0); + return true; + } else if (action == "hand_wave") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_HAND_WAVE, 1, 0, 0, direction); + return true; + } else if (action == "windmill") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_WINDMILL, steps, speed, 0, amount); + return true; + } else if (action == "takeoff") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_TAKEOFF, steps, speed, 0, amount); + return true; + } else if (action == "fitness") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_FITNESS, steps, speed, 0, amount); + return true; + } else if (action == "greeting") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_GREETING, steps, 0, direction, 0); + return true; + } else if (action == "shy") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_SHY, steps, 0, direction, 0); + return true; + } else if (action == "radio_calisthenics") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_RADIO_CALISTHENICS, 1, 0, 0, 0); + return true; + } else if (action == "magic_circle") { + if (!has_hands_) { + return "错误:此动作需要手部舵机支持"; + } + QueueAction(ACTION_MAGIC_CIRCLE, 1, 0, 0, 0); + return true; + } else { + return "错误:无效的动作名称。可用动作:walk, turn, jump, swing, moonwalk, bend, shake_leg, updown, whirlwind_leg, sit, showcase, home, hands_up, hands_down, hand_wave, windmill, takeoff, fitness, greeting, shy, radio_calisthenics, magic_circle"; + } + }); + + + // 舵机序列工具(支持分段发送,每次发送一个序列,自动排队执行) + mcp_server.AddTool( + "self.otto.servo_sequences", + "AI自定义动作编程(即兴动作)。支持分段发送序列:超过5个序列建议AI可以连续多次调用此工具,每次发送一个短序列,系统会自动排队按顺序执行。支持普通移动和振荡器两种模式。" + "机器人结构:双手可上下摆动,双腿可内收外展,双脚可上下翻转。" + "舵机说明:" + "ll(左腿):内收外展,0度=完全外展,90度=中立,180度=完全内收;" + "rl(右腿):内收外展,0度=完全内收,90度=中立,180度=完全外展;" + "lf(左脚):上下翻转,0度=完全向上,90度=水平,180度=完全向下;" + "rf(右脚):上下翻转,0度=完全向下,90度=水平,180度=完全向上;" + "lh(左手):上下摆动,0度=完全向下,90度=水平,180度=完全向上;" + "rh(右手):上下摆动,0度=完全向上,90度=水平,180度=完全向下;" + "sequence: 单个序列对象,包含'a'动作数组,顶层可选参数:" + "'d'(序列执行完成后延迟毫秒数,用于序列之间的停顿)。" + "每个动作对象包含:" + "普通模式:'s'舵机位置对象(键名:ll/rl/lf/rf/lh/rh,值:0-180度),'v'移动速度100-3000毫秒(默认1000),'d'动作后延迟毫秒数(默认0);" + "振荡模式:'osc'振荡器对象,包含'a'振幅对象(各舵机振幅10-90度,默认20度),'o'中心角度对象(各舵机振荡中心绝对角度0-180度,默认90度),'ph'相位差对象(各舵机相位差,度,0-360度,默认0度),'p'周期100-3000毫秒(默认500),'c'周期数0.1-20.0(默认5.0);" + "使用方式:AI可以连续多次调用此工具,每次发送一个序列,系统会自动排队按顺序执行。" + "重要说明:左右腿脚震荡的时候,有一只脚必须在90度,否则会损坏机器人,如果发送多个序列(序列数>1),完成所有序列后需要复位时,AI应该最后单独调用self.otto.home工具进行复位,不要在序列中设置复位参数。" + "普通模式示例:发送3个序列,最后调用复位:" + "第1次调用{\"sequence\":\"{\\\"a\\\":[{\\\"s\\\":{\\\"ll\\\":100},\\\"v\\\":1000}],\\\"d\\\":500}\"}," + "第2次调用{\"sequence\":\"{\\\"a\\\":[{\\\"s\\\":{\\\"ll\\\":90},\\\"v\\\":800}],\\\"d\\\":500}\"}," + "第3次调用{\"sequence\":\"{\\\"a\\\":[{\\\"s\\\":{\\\"ll\\\":80},\\\"v\\\":800}]}\"}," + "最后调用self.otto.home工具进行复位。" + "振荡器模式示例:" + "示例1-双臂同步摆动:{\"sequence\":\"{\\\"a\\\":[{\\\"osc\\\":{\\\"a\\\":{\\\"lh\\\":30,\\\"rh\\\":30},\\\"o\\\":{\\\"lh\\\":90,\\\"rh\\\":-90},\\\"p\\\":500,\\\"c\\\":5.0}}],\\\"d\\\":0}\"};" + "示例2-双腿交替振荡(波浪效果):{\"sequence\":\"{\\\"a\\\":[{\\\"osc\\\":{\\\"a\\\":{\\\"ll\\\":20,\\\"rl\\\":20},\\\"o\\\":{\\\"ll\\\":90,\\\"rl\\\":-90},\\\"ph\\\":{\\\"rl\\\":180},\\\"p\\\":600,\\\"c\\\":3.0}}],\\\"d\\\":0}\"};" + "示例3-单腿振荡配合固定脚(安全):{\"sequence\":\"{\\\"a\\\":[{\\\"osc\\\":{\\\"a\\\":{\\\"ll\\\":45},\\\"o\\\":{\\\"ll\\\":90,\\\"lf\\\":90},\\\"p\\\":400,\\\"c\\\":4.0}}],\\\"d\\\":0}\"};" + "示例4-复杂多舵机振荡(手和腿):{\"sequence\":\"{\\\"a\\\":[{\\\"osc\\\":{\\\"a\\\":{\\\"lh\\\":25,\\\"rh\\\":25,\\\"ll\\\":15},\\\"o\\\":{\\\"lh\\\":90,\\\"rh\\\":90,\\\"ll\\\":90,\\\"lf\\\":90},\\\"ph\\\":{\\\"rh\\\":180},\\\"p\\\":800,\\\"c\\\":6.0}}],\\\"d\\\":500}\"};" + "示例5-快速摇摆:{\"sequence\":\"{\\\"a\\\":[{\\\"osc\\\":{\\\"a\\\":{\\\"ll\\\":30,\\\"rl\\\":30},\\\"o\\\":{\\\"ll\\\":90,\\\"rl\\\":90},\\\"ph\\\":{\\\"rl\\\":180},\\\"p\\\":300,\\\"c\\\":10.0}}],\\\"d\\\":0}\"}。", + PropertyList({Property("sequence", kPropertyTypeString, + "{\"a\":[{\"s\":{\"ll\":90,\"rl\":90},\"v\":1000}]}")}), + [this](const PropertyList& properties) -> ReturnValue { + std::string sequence = properties["sequence"].value(); + // 检查是否是JSON对象(可能是字符串格式或已解析的对象) + // 如果sequence是JSON字符串,直接使用;如果是对象字符串,也需要使用 + QueueServoSequence(sequence.c_str()); + return true; + }); + + + mcp_server.AddTool("self.otto.stop", "立即停止所有动作并复位", PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + if (action_task_handle_ != nullptr) { + vTaskDelete(action_task_handle_); + action_task_handle_ = nullptr; + } + is_action_in_progress_ = false; + xQueueReset(action_queue_); + + QueueAction(ACTION_HOME, 1, 1000, 1, 0); + return true; + }); + + mcp_server.AddTool( + "self.otto.set_trim", + "校准单个舵机位置。设置指定舵机的微调参数以调整机器人的初始站立姿态,设置将永久保存。" + "servo_type: 舵机类型(left_leg/right_leg/left_foot/right_foot/left_hand/right_hand); " + "trim_value: 微调值(-50到50度)", + PropertyList({Property("servo_type", kPropertyTypeString, "left_leg"), + Property("trim_value", kPropertyTypeInteger, 0, -50, 50)}), + [this](const PropertyList& properties) -> ReturnValue { + std::string servo_type = properties["servo_type"].value(); + int trim_value = properties["trim_value"].value(); + + ESP_LOGI(TAG, "设置舵机微调: %s = %d度", servo_type.c_str(), trim_value); + + // 获取当前所有微调值 + Settings settings("otto_trims", true); + int left_leg = settings.GetInt("left_leg", 0); + int right_leg = settings.GetInt("right_leg", 0); + int left_foot = settings.GetInt("left_foot", 0); + int right_foot = settings.GetInt("right_foot", 0); + int left_hand = settings.GetInt("left_hand", 0); + int right_hand = settings.GetInt("right_hand", 0); + + // 更新指定舵机的微调值 + if (servo_type == "left_leg") { + left_leg = trim_value; + settings.SetInt("left_leg", left_leg); + } else if (servo_type == "right_leg") { + right_leg = trim_value; + settings.SetInt("right_leg", right_leg); + } else if (servo_type == "left_foot") { + left_foot = trim_value; + settings.SetInt("left_foot", left_foot); + } else if (servo_type == "right_foot") { + right_foot = trim_value; + settings.SetInt("right_foot", right_foot); + } else if (servo_type == "left_hand") { + if (!has_hands_) { + return "错误:机器人没有配置手部舵机"; + } + left_hand = trim_value; + settings.SetInt("left_hand", left_hand); + } else if (servo_type == "right_hand") { + if (!has_hands_) { + return "错误:机器人没有配置手部舵机"; + } + right_hand = trim_value; + settings.SetInt("right_hand", right_hand); + } else { + return "错误:无效的舵机类型,请使用: left_leg, right_leg, left_foot, " + "right_foot, left_hand, right_hand"; + } + + otto_.SetTrims(left_leg, right_leg, left_foot, right_foot, left_hand, right_hand); + + QueueAction(ACTION_JUMP, 1, 500, 0, 0); + + return "舵机 " + servo_type + " 微调设置为 " + std::to_string(trim_value) + + " 度,已永久保存"; + }); + + mcp_server.AddTool("self.otto.get_trims", "获取当前的舵机微调设置", PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + Settings settings("otto_trims", false); + + int left_leg = settings.GetInt("left_leg", 0); + int right_leg = settings.GetInt("right_leg", 0); + int left_foot = settings.GetInt("left_foot", 0); + int right_foot = settings.GetInt("right_foot", 0); + int left_hand = settings.GetInt("left_hand", 0); + int right_hand = settings.GetInt("right_hand", 0); + + std::string result = + "{\"left_leg\":" + std::to_string(left_leg) + + ",\"right_leg\":" + std::to_string(right_leg) + + ",\"left_foot\":" + std::to_string(left_foot) + + ",\"right_foot\":" + std::to_string(right_foot) + + ",\"left_hand\":" + std::to_string(left_hand) + + ",\"right_hand\":" + std::to_string(right_hand) + "}"; + + ESP_LOGI(TAG, "获取微调设置: %s", result.c_str()); + return result; + }); + + mcp_server.AddTool("self.otto.get_status", "获取机器人状态,返回 moving 或 idle", + PropertyList(), [this](const PropertyList& properties) -> ReturnValue { + return is_action_in_progress_ ? "moving" : "idle"; + }); + + mcp_server.AddTool("self.battery.get_level", "获取机器人电池电量和充电状态", PropertyList(), + [](const PropertyList& properties) -> ReturnValue { + auto& board = Board::GetInstance(); + int level = 0; + bool charging = false; + bool discharging = false; + board.GetBatteryLevel(level, charging, discharging); + + std::string status = + "{\"level\":" + std::to_string(level) + + ",\"charging\":" + (charging ? "true" : "false") + "}"; + return status; + }); + + mcp_server.AddTool("self.otto.get_ip", "获取机器人WiFi IP地址", PropertyList(), + [](const PropertyList& properties) -> ReturnValue { + auto& wifi_station = WifiStation::GetInstance(); + std::string ip = wifi_station.GetIpAddress(); + if (ip.empty()) { + return "{\"ip\":\"\",\"connected\":false}"; + } + std::string status = "{\"ip\":\"" + ip + "\",\"connected\":true}"; + return status; + }); + + ESP_LOGI(TAG, "MCP工具注册完成"); + } + + ~OttoController() { + if (action_task_handle_ != nullptr) { + vTaskDelete(action_task_handle_); + action_task_handle_ = nullptr; + } + vQueueDelete(action_queue_); + } +}; + +static OttoController* g_otto_controller = nullptr; + +void InitializeOttoController() { + if (g_otto_controller == nullptr) { + g_otto_controller = new OttoController(); + ESP_LOGI(TAG, "Otto控制器已初始化并注册MCP工具"); + } +} diff --git a/main/boards/otto-robot/otto_emoji_display.cc b/main/boards/otto-robot/otto_emoji_display.cc new file mode 100644 index 0000000..63b6bd0 --- /dev/null +++ b/main/boards/otto-robot/otto_emoji_display.cc @@ -0,0 +1,182 @@ +#include "otto_emoji_display.h" + +#include + +#include + +#include "assets/lang_config.h" +#include "display/lvgl_display/emoji_collection.h" +#include "display/lvgl_display/lvgl_image.h" +#include "display/lvgl_display/lvgl_theme.h" +#include "otto_emoji_gif.h" + +#define TAG "OttoEmojiDisplay" +OttoEmojiDisplay::OttoEmojiDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : SpiLcdDisplay(panel_io, panel, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + InitializeOttoEmojis(); + SetupChatLabel(); + SetupPreviewImage(); +} + +void OttoEmojiDisplay::SetupPreviewImage() { + DisplayLockGuard lock(this); + lv_obj_set_size(preview_image_, width_ , height_ ); +} + +void OttoEmojiDisplay::InitializeOttoEmojis() { + ESP_LOGI(TAG, "初始化Otto GIF表情"); + + auto otto_emoji_collection = std::make_shared(); + + // 中性/平静类表情 -> staticstate + otto_emoji_collection->AddEmoji("staticstate", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("neutral", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("relaxed", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("sleepy", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + otto_emoji_collection->AddEmoji("idle", new LvglRawImage((void*)staticstate.data, staticstate.data_size)); + + // 积极/开心类表情 -> happy + otto_emoji_collection->AddEmoji("happy", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("laughing", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("funny", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("loving", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("confident", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("winking", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("cool", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("delicious", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("kissy", new LvglRawImage((void*)happy.data, happy.data_size)); + otto_emoji_collection->AddEmoji("silly", new LvglRawImage((void*)happy.data, happy.data_size)); + + // 悲伤类表情 -> sad + otto_emoji_collection->AddEmoji("sad", new LvglRawImage((void*)sad.data, sad.data_size)); + otto_emoji_collection->AddEmoji("crying", new LvglRawImage((void*)sad.data, sad.data_size)); + + // 愤怒类表情 -> anger + otto_emoji_collection->AddEmoji("anger", new LvglRawImage((void*)anger.data, anger.data_size)); + otto_emoji_collection->AddEmoji("angry", new LvglRawImage((void*)anger.data, anger.data_size)); + + // 惊讶类表情 -> scare + otto_emoji_collection->AddEmoji("scare", new LvglRawImage((void*)scare.data, scare.data_size)); + otto_emoji_collection->AddEmoji("surprised", new LvglRawImage((void*)scare.data, scare.data_size)); + otto_emoji_collection->AddEmoji("shocked", new LvglRawImage((void*)scare.data, scare.data_size)); + + // 思考/困惑类表情 -> buxue + otto_emoji_collection->AddEmoji("buxue", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("thinking", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("confused", new LvglRawImage((void*)buxue.data, buxue.data_size)); + otto_emoji_collection->AddEmoji("embarrassed", new LvglRawImage((void*)buxue.data, buxue.data_size)); + + // 将表情集合添加到主题中 + auto& theme_manager = LvglThemeManager::GetInstance(); + auto light_theme = theme_manager.GetTheme("light"); + auto dark_theme = theme_manager.GetTheme("dark"); + + if (light_theme != nullptr) { + light_theme->set_emoji_collection(otto_emoji_collection); + } + if (dark_theme != nullptr) { + dark_theme->set_emoji_collection(otto_emoji_collection); + } + + // 设置默认表情为staticstate + SetEmotion("staticstate"); + + ESP_LOGI(TAG, "Otto GIF表情初始化完成"); +} + +void OttoEmojiDisplay::SetupChatLabel() { + DisplayLockGuard lock(this); + + if (chat_message_label_) { + lv_obj_del(chat_message_label_); + } + + chat_message_label_ = lv_label_create(container_); + lv_label_set_text(chat_message_label_, ""); + lv_obj_set_width(chat_message_label_, width_ * 0.9); // 限制宽度为屏幕宽度的 90% + lv_label_set_long_mode(chat_message_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_obj_set_style_text_align(chat_message_label_, LV_TEXT_ALIGN_CENTER, 0); // 设置文本居中对齐 + lv_obj_set_style_text_color(chat_message_label_, lv_color_white(), 0); + SetTheme(LvglThemeManager::GetInstance().GetTheme("dark")); +} + +LV_FONT_DECLARE(OTTO_ICON_FONT); +void OttoEmojiDisplay::SetStatus(const char* status) { + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + DisplayLockGuard lock(this); + if (!status) { + ESP_LOGE(TAG, "SetStatus: status is nullptr"); + return; + } + + if (strcmp(status, Lang::Strings::LISTENING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x84\xB0"); // U+F130 麦克风图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::SPEAKING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x80\xA8"); // U+F028 说话图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::CONNECTING) == 0) { + lv_obj_set_style_text_font(status_label_, &OTTO_ICON_FONT, 0); + lv_label_set_text(status_label_, "\xEF\x83\x81"); // U+F0c1 连接图标 + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + return; + } else if (strcmp(status, Lang::Strings::STANDBY) == 0) { + lv_obj_set_style_text_font(status_label_, text_font, 0); + lv_label_set_text(status_label_, ""); + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + return; + } + + lv_obj_set_style_text_font(status_label_, text_font, 0); + lv_label_set_text(status_label_, status); + lv_obj_clear_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_clear_flag(network_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_clear_flag(battery_label_, LV_OBJ_FLAG_HIDDEN); +} + +void OttoEmojiDisplay::SetPreviewImage(std::unique_ptr image) { + DisplayLockGuard lock(this); + if (preview_image_ == nullptr) { + ESP_LOGE(TAG, "Preview image is not initialized"); + return; + } + + if (image == nullptr) { + esp_timer_stop(preview_timer_); + lv_obj_remove_flag(emoji_box_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(preview_image_, LV_OBJ_FLAG_HIDDEN); + preview_image_cached_.reset(); + if (gif_controller_) { + gif_controller_->Start(); + } + return; + } + + preview_image_cached_ = std::move(image); + auto img_dsc = preview_image_cached_->image_dsc(); + // 设置图片源并显示预览图片 + lv_image_set_src(preview_image_, img_dsc); + lv_image_set_rotation(preview_image_, -900); + if (img_dsc->header.w > 0 && img_dsc->header.h > 0) { + // zoom factor 1.0 + lv_image_set_scale(preview_image_, 256 * width_ / img_dsc->header.w); + } + + // Hide emoji_box_ + if (gif_controller_) { + gif_controller_->Stop(); + } + lv_obj_add_flag(emoji_box_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(preview_image_, LV_OBJ_FLAG_HIDDEN); + esp_timer_stop(preview_timer_); + ESP_ERROR_CHECK(esp_timer_start_once(preview_timer_, PREVIEW_IMAGE_DURATION_MS * 1000)); +} \ No newline at end of file diff --git a/main/boards/otto-robot/otto_emoji_display.h b/main/boards/otto-robot/otto_emoji_display.h new file mode 100644 index 0000000..0d9accc --- /dev/null +++ b/main/boards/otto-robot/otto_emoji_display.h @@ -0,0 +1,24 @@ +#pragma once + +#include "display/lcd_display.h" + +/** + * @brief Otto机器人GIF表情显示类 + * 继承SpiLcdDisplay,通过EmojiCollection添加GIF表情支持 + */ +class OttoEmojiDisplay : public SpiLcdDisplay { + public: + /** + * @brief 构造函数,参数与SpiLcdDisplay相同 + */ + OttoEmojiDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy); + + virtual ~OttoEmojiDisplay() = default; + virtual void SetStatus(const char* status) override; + virtual void SetPreviewImage(std::unique_ptr image) override; + + private: + void InitializeOttoEmojis(); + void SetupChatLabel(); + void SetupPreviewImage(); +}; \ No newline at end of file diff --git a/main/boards/otto-robot/otto_icon_font.c b/main/boards/otto-robot/otto_icon_font.c new file mode 100644 index 0000000..dc05cce --- /dev/null +++ b/main/boards/otto-robot/otto_icon_font.c @@ -0,0 +1,121 @@ +/******************************************************************************* + * Size: 20 px + * Bpp: 1 + * Opts: --bpp 1 --size 20 --no-compress --stride 1 --align 1 --font fontawesome-webfont.ttf --range 61744,61633,61480 --format lvgl -o OTTO_ICON_FONT.c + ******************************************************************************/ + +#ifdef __has_include +#if __has_include("lvgl.h") +#ifndef LV_LVGL_H_INCLUDE_SIMPLE +#define LV_LVGL_H_INCLUDE_SIMPLE +#endif +#endif +#endif + +#ifdef LV_LVGL_H_INCLUDE_SIMPLE +#include "lvgl.h" +#else +#include "lvgl/lvgl.h" +#endif + +#ifndef ENABLE_OTTO_ICON_FONT +#define ENABLE_OTTO_ICON_FONT 1 +#endif + +#if ENABLE_OTTO_ICON_FONT + +/*----------------- + * BITMAPS + *----------------*/ + +/*Store the image of the glyphs*/ +static LV_ATTRIBUTE_LARGE_CONST const uint8_t glyph_bitmap[] = { + /* U+F028 "" */ + 0x0, 0x6, 0x0, 0x10, 0xe0, 0x6, 0x6, 0x3, 0xc6, 0x60, 0xf8, 0x65, 0xff, 0x24, 0xff, 0xe6, 0x4f, 0xfc, 0x49, 0xff, 0x89, 0x3f, 0xf3, 0x27, 0xfe, 0x49, 0x87, 0xc3, 0x20, 0x78, 0xcc, 0x3, 0x3, 0x0, + 0x21, 0xc0, 0x0, 0x30, + + /* U+F0C1 "" */ + 0x1e, 0x0, 0xf, 0xc0, 0x7, 0x38, 0x3, 0x87, 0x0, 0xc0, 0xc0, 0x30, 0xb0, 0x7, 0x3c, 0x0, 0xef, 0x0, 0x1f, 0xfe, 0x3, 0xff, 0xc0, 0x7, 0x38, 0x3, 0xe7, 0x0, 0xd0, 0xc0, 0x30, 0x30, 0x6, 0x1c, 0x0, + 0xce, 0x0, 0x1f, 0x0, 0x3, 0x80, + + /* U+F130 "" */ + 0x7, 0x0, 0xfe, 0x7, 0xf0, 0x3f, 0x81, 0xfc, 0xf, 0xe0, 0x7f, 0x13, 0xf9, 0x9f, 0xcc, 0xfe, 0x67, 0xf3, 0xbf, 0xb4, 0x73, 0x18, 0x30, 0x7f, 0x0, 0x60, 0x2, 0x1, 0xff, 0x0}; + +/*--------------------- + * GLYPH DESCRIPTION + *--------------------*/ + +static const lv_font_fmt_txt_glyph_dsc_t glyph_dsc[] = {{.bitmap_index = 0, .adv_w = 0, .box_w = 0, .box_h = 0, .ofs_x = 0, .ofs_y = 0} /* id = 0 reserved */, + {.bitmap_index = 0, .adv_w = 297, .box_w = 19, .box_h = 16, .ofs_x = 0, .ofs_y = -1}, + {.bitmap_index = 38, .adv_w = 297, .box_w = 18, .box_h = 18, .ofs_x = 0, .ofs_y = -1}, + {.bitmap_index = 79, .adv_w = 206, .box_w = 13, .box_h = 18, .ofs_x = 0, .ofs_y = -1}}; + +/*--------------------- + * CHARACTER MAPPING + *--------------------*/ + +static const uint16_t unicode_list_0[] = {0x0, 0x99, 0x108}; + +/*Collect the unicode lists and glyph_id offsets*/ +static const lv_font_fmt_txt_cmap_t cmaps[] = { + {.range_start = 61480, .range_length = 265, .glyph_id_start = 1, .unicode_list = unicode_list_0, .glyph_id_ofs_list = NULL, .list_length = 3, .type = LV_FONT_FMT_TXT_CMAP_SPARSE_TINY}}; + +/*-------------------- + * ALL CUSTOM DATA + *--------------------*/ + +#if LVGL_VERSION_MAJOR == 8 +/*Store all the custom data of the font*/ +static lv_font_fmt_txt_glyph_cache_t cache; +#endif + +#if LVGL_VERSION_MAJOR >= 8 +static const lv_font_fmt_txt_dsc_t otto_icon_font_dsc = { +#else +static lv_font_fmt_txt_dsc_t otto_icon_font_dsc = { +#endif + .glyph_bitmap = glyph_bitmap, + .glyph_dsc = glyph_dsc, + .cmaps = cmaps, + .kern_dsc = NULL, + .kern_scale = 0, + .cmap_num = 1, + .bpp = 1, + .kern_classes = 0, + .bitmap_format = 0, +#if LVGL_VERSION_MAJOR == 8 + .cache = &cache +#endif + +}; + +/*----------------- + * PUBLIC FONT + *----------------*/ + +/*Initialize a public general font descriptor*/ +#if LVGL_VERSION_MAJOR >= 8 +const lv_font_t OTTO_ICON_FONT = { +#else +lv_font_t OTTO_ICON_FONT = { +#endif + .get_glyph_dsc = lv_font_get_glyph_dsc_fmt_txt, /*Function pointer to get glyph's data*/ + .get_glyph_bitmap = lv_font_get_bitmap_fmt_txt, /*Function pointer to get glyph's bitmap*/ + .line_height = 18, /*The maximum line height required by the font*/ + .base_line = 1, /*Baseline measured from the bottom of the line*/ +#if !(LVGL_VERSION_MAJOR == 6 && LVGL_VERSION_MINOR == 0) + .subpx = LV_FONT_SUBPX_NONE, +#endif +#if LV_VERSION_CHECK(7, 4, 0) || LVGL_VERSION_MAJOR >= 8 + .underline_position = 0, + .underline_thickness = 0, +#endif + .static_bitmap = 0, + .dsc = &otto_icon_font_dsc, /*The custom font data. Will be accessed by `get_glyph_bitmap/dsc` */ +#if LV_VERSION_CHECK(8, 2, 0) || LVGL_VERSION_MAJOR >= 9 + .fallback = NULL, +#endif + .user_data = NULL, +}; + +#endif /*#if ENABLE_OTTO_ICON_FONT*/ diff --git a/main/boards/otto-robot/otto_movements.cc b/main/boards/otto-robot/otto_movements.cc new file mode 100644 index 0000000..9d11f12 --- /dev/null +++ b/main/boards/otto-robot/otto_movements.cc @@ -0,0 +1,964 @@ +#include "otto_movements.h" + +#include + +#include "freertos/idf_additions.h" +#include "oscillator.h" + +static const char* TAG = "OttoMovements"; + +#define HAND_HOME_POSITION 45 + +Otto::Otto() { + is_otto_resting_ = false; + has_hands_ = false; + // 初始化所有舵机管脚为-1(未连接) + for (int i = 0; i < SERVO_COUNT; i++) { + servo_pins_[i] = -1; + servo_trim_[i] = 0; + } +} + +Otto::~Otto() { + DetachServos(); +} + +unsigned long IRAM_ATTR millis() { + return (unsigned long)(esp_timer_get_time() / 1000ULL); +} + +void Otto::Init(int left_leg, int right_leg, int left_foot, int right_foot, int left_hand, + int right_hand) { + servo_pins_[LEFT_LEG] = left_leg; + servo_pins_[RIGHT_LEG] = right_leg; + servo_pins_[LEFT_FOOT] = left_foot; + servo_pins_[RIGHT_FOOT] = right_foot; + servo_pins_[LEFT_HAND] = left_hand; + servo_pins_[RIGHT_HAND] = right_hand; + + // 检查是否有手部舵机 + has_hands_ = (left_hand != -1 && right_hand != -1); + + AttachServos(); + is_otto_resting_ = false; +} + +/////////////////////////////////////////////////////////////////// +//-- ATTACH & DETACH FUNCTIONS ----------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::AttachServos() { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Attach(servo_pins_[i]); + } + } +} + +void Otto::DetachServos() { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Detach(); + } + } +} + +/////////////////////////////////////////////////////////////////// +//-- OSCILLATORS TRIMS ------------------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::SetTrims(int left_leg, int right_leg, int left_foot, int right_foot, int left_hand, + int right_hand) { + servo_trim_[LEFT_LEG] = left_leg; + servo_trim_[RIGHT_LEG] = right_leg; + servo_trim_[LEFT_FOOT] = left_foot; + servo_trim_[RIGHT_FOOT] = right_foot; + + if (has_hands_) { + servo_trim_[LEFT_HAND] = left_hand; + servo_trim_[RIGHT_HAND] = right_hand; + } + + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetTrim(servo_trim_[i]); + } + } +} + +/////////////////////////////////////////////////////////////////// +//-- BASIC MOTION FUNCTIONS -------------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::MoveServos(int time, int servo_target[]) { + if (GetRestState() == true) { + SetRestState(false); + } + + final_time_ = millis() + time; + if (time > 10) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + increment_[i] = (servo_target[i] - servo_[i].GetPosition()) / (time / 10.0); + } + } + + for (int iteration = 1; millis() < final_time_; iteration++) { + partial_time_ = millis() + 10; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_[i].GetPosition() + increment_[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(10)); + } + } else { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_target[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(time)); + } + + // final adjustment to the target. + bool f = true; + int adjustment_count = 0; + while (f && adjustment_count < 10) { + f = false; + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1 && servo_target[i] != servo_[i].GetPosition()) { + f = true; + break; + } + } + if (f) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetPosition(servo_target[i]); + } + } + vTaskDelay(pdMS_TO_TICKS(10)); + adjustment_count++; + } + }; +} + +void Otto::MoveSingle(int position, int servo_number) { + if (position > 180) + position = 90; + if (position < 0) + position = 90; + + if (GetRestState() == true) { + SetRestState(false); + } + + if (servo_number >= 0 && servo_number < SERVO_COUNT && servo_pins_[servo_number] != -1) { + servo_[servo_number].SetPosition(position); + } +} + +void Otto::OscillateServos(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float cycle = 1) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetO(offset[i]); + servo_[i].SetA(amplitude[i]); + servo_[i].SetT(period); + servo_[i].SetPh(phase_diff[i]); + } + } + + double ref = millis(); + double end_time = period * cycle + ref; + + while (millis() < end_time) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].Refresh(); + } + } + vTaskDelay(5); + } + vTaskDelay(pdMS_TO_TICKS(10)); +} + +void Otto::Execute(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps = 1.0) { + if (GetRestState() == true) { + SetRestState(false); + } + + int cycles = (int)steps; + + //-- Execute complete cycles + if (cycles >= 1) + for (int i = 0; i < cycles; i++) + OscillateServos(amplitude, offset, period, phase_diff); + + //-- Execute the final not complete cycle + OscillateServos(amplitude, offset, period, phase_diff, (float)steps - cycles); + vTaskDelay(pdMS_TO_TICKS(10)); +} + +//--------------------------------------------------------- +//-- Execute2: 使用绝对角度作为振荡中心 +//-- Parameters: +//-- amplitude: 振幅数组(每个舵机的振荡幅度) +//-- center_angle: 绝对角度数组(0-180度),作为振荡中心位置 +//-- period: 周期(毫秒) +//-- phase_diff: 相位差数组(弧度) +//-- steps: 步数/周期数(可为小数) +//--------------------------------------------------------- +void Otto::Execute2(int amplitude[SERVO_COUNT], int center_angle[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps = 1.0) { + if (GetRestState() == true) { + SetRestState(false); + } + + // 将绝对角度转换为offset(offset = center_angle - 90) + int offset[SERVO_COUNT]; + for (int i = 0; i < SERVO_COUNT; i++) { + offset[i] = center_angle[i] - 90; + } + + int cycles = (int)steps; + + //-- Execute complete cycles + if (cycles >= 1) + for (int i = 0; i < cycles; i++) + OscillateServos(amplitude, offset, period, phase_diff); + + //-- Execute the final not complete cycle + OscillateServos(amplitude, offset, period, phase_diff, (float)steps - cycles); + vTaskDelay(pdMS_TO_TICKS(10)); +} + +/////////////////////////////////////////////////////////////////// +//-- HOME = Otto at rest position -------------------------------// +/////////////////////////////////////////////////////////////////// +void Otto::Home(bool hands_down) { + if (is_otto_resting_ == false) { // Go to rest position only if necessary + // 为所有舵机准备初始位置值 + int homes[SERVO_COUNT]; + for (int i = 0; i < SERVO_COUNT; i++) { + if (i == LEFT_HAND || i == RIGHT_HAND) { + if (hands_down) { + // 如果需要复位手部,设置为默认值 + if (i == LEFT_HAND) { + homes[i] = HAND_HOME_POSITION; + } else { // RIGHT_HAND + homes[i] = 180 - HAND_HOME_POSITION; // 右手镜像位置 + } + } else { + // 如果不需要复位手部,保持当前位置 + homes[i] = servo_[i].GetPosition(); + } + } else { + // 腿部和脚部舵机始终复位 + homes[i] = 90; + } + } + + MoveServos(700, homes); + is_otto_resting_ = true; + } + + vTaskDelay(pdMS_TO_TICKS(200)); +} + +bool Otto::GetRestState() { + return is_otto_resting_; +} + +void Otto::SetRestState(bool state) { + is_otto_resting_ = state; +} + +/////////////////////////////////////////////////////////////////// +//-- PREDETERMINED MOTION SEQUENCES -----------------------------// +/////////////////////////////////////////////////////////////////// +//-- Otto movement: Jump +//-- Parameters: +//-- steps: Number of steps +//-- T: Period +//--------------------------------------------------------- +void Otto::Jump(float steps, int period) { + int up[SERVO_COUNT] = {90, 90, 150, 30, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + MoveServos(period, up); + int down[SERVO_COUNT] = {90, 90, 90, 90, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + MoveServos(period, down); +} + +//--------------------------------------------------------- +//-- Otto gait: Walking (forward or backward) +//-- Parameters: +//-- * steps: Number of steps +//-- * T : Period +//-- * Dir: Direction: FORWARD / BACKWARD +//-- * amount: 手部摆动幅度, 0表示不摆动 +//--------------------------------------------------------- +void Otto::Walk(float steps, int period, int dir, int amount) { + //-- Oscillator parameters for walking + //-- Hip sevos are in phase + //-- Feet servos are in phase + //-- Hip and feet are 90 degrees out of phase + //-- -90 : Walk forward + //-- 90 : Walk backward + //-- Feet servos also have the same offset (for tiptoe a little bit) + int A[SERVO_COUNT] = {30, 30, 30, 30, 0, 0}; + int O[SERVO_COUNT] = {0, 0, 5, -5, HAND_HOME_POSITION - 90, HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(dir * -90), DEG2RAD(dir * -90), 0, 0}; + + // 如果amount>0且有手部舵机,设置手部振幅和相位 + if (amount > 0 && has_hands_) { + // 手臂振幅使用传入的amount参数 + A[LEFT_HAND] = amount; + A[RIGHT_HAND] = amount; + + // 左手与右腿同相,右手与左腿同相,使得机器人走路时手臂自然摆动 + phase_diff[LEFT_HAND] = phase_diff[RIGHT_LEG]; // 左手与右腿同相 + phase_diff[RIGHT_HAND] = phase_diff[LEFT_LEG]; // 右手与左腿同相 + } else { + A[LEFT_HAND] = 0; + A[RIGHT_HAND] = 0; + } + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Turning (left or right) +//-- Parameters: +//-- * Steps: Number of steps +//-- * T: Period +//-- * Dir: Direction: LEFT / RIGHT +//-- * amount: 手部摆动幅度, 0表示不摆动 +//--------------------------------------------------------- +void Otto::Turn(float steps, int period, int dir, int amount) { + //-- Same coordination than for walking (see Otto::walk) + //-- The Amplitudes of the hip's oscillators are not igual + //-- When the right hip servo amplitude is higher, the steps taken by + //-- the right leg are bigger than the left. So, the robot describes an + //-- left arc + int A[SERVO_COUNT] = {30, 30, 30, 30, 0, 0}; + int O[SERVO_COUNT] = {0, 0, 5, -5, HAND_HOME_POSITION - 90, HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(-90), DEG2RAD(-90), 0, 0}; + + if (dir == LEFT) { + A[0] = 30; //-- Left hip servo + A[1] = 0; //-- Right hip servo + } else { + A[0] = 0; + A[1] = 30; + } + + // 如果amount>0且有手部舵机,设置手部振幅和相位 + if (amount > 0 && has_hands_) { + // 手臂振幅使用传入的amount参数 + A[LEFT_HAND] = amount; + A[RIGHT_HAND] = amount; + + // 转向时手臂摆动相位:左手与左腿同相,右手与右腿同相,增强转向效果 + phase_diff[LEFT_HAND] = phase_diff[LEFT_LEG]; // 左手与左腿同相 + phase_diff[RIGHT_HAND] = phase_diff[RIGHT_LEG]; // 右手与右腿同相 + } else { + A[LEFT_HAND] = 0; + A[RIGHT_HAND] = 0; + } + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Lateral bend +//-- Parameters: +//-- steps: Number of bends +//-- T: Period of one bend +//-- dir: RIGHT=Right bend LEFT=Left bend +//--------------------------------------------------------- +void Otto::Bend(int steps, int period, int dir) { + // Parameters of all the movements. Default: Left bend + int bend1[SERVO_COUNT] = {90, 90, 62, 35, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int bend2[SERVO_COUNT] = {90, 90, 62, 105, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int homes[SERVO_COUNT] = {90, 90, 90, 90, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + + // Time of one bend, constrained in order to avoid movements too fast. + // T=max(T, 600); + // Changes in the parameters if right direction is chosen + if (dir == -1) { + bend1[2] = 180 - 35; + bend1[3] = 180 - 60; // Not 65. Otto is unbalanced + bend2[2] = 180 - 105; + bend2[3] = 180 - 60; + } + + // Time of the bend movement. Fixed parameter to avoid falls + int T2 = 800; + + // Bend movement + for (int i = 0; i < steps; i++) { + MoveServos(T2 / 2, bend1); + MoveServos(T2 / 2, bend2); + vTaskDelay(pdMS_TO_TICKS(period * 0.8)); + MoveServos(500, homes); + } +} + +//--------------------------------------------------------- +//-- Otto gait: Shake a leg +//-- Parameters: +//-- steps: Number of shakes +//-- T: Period of one shake +//-- dir: RIGHT=Right leg LEFT=Left leg +//--------------------------------------------------------- +void Otto::ShakeLeg(int steps, int period, int dir) { + // This variable change the amount of shakes + int numberLegMoves = 2; + + // Parameters of all the movements. Default: Right leg + int shake_leg1[SERVO_COUNT] = {90, 90, 58, 35, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int shake_leg2[SERVO_COUNT] = {90, 90, 58, 120, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int shake_leg3[SERVO_COUNT] = {90, 90, 58, 60, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int homes[SERVO_COUNT] = {90, 90, 90, 90, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + + // Changes in the parameters if left leg is chosen + if (dir == LEFT) { + shake_leg1[2] = 180 - 35; + shake_leg1[3] = 180 - 58; + shake_leg2[2] = 180 - 120; + shake_leg2[3] = 180 - 58; + shake_leg3[2] = 180 - 60; + shake_leg3[3] = 180 - 58; + } + + // Time of the bend movement. Fixed parameter to avoid falls + int T2 = 1000; + // Time of one shake, constrained in order to avoid movements too fast. + period = period - T2; + period = std::max(period, 200 * numberLegMoves); + + for (int j = 0; j < steps; j++) { + // Bend movement + MoveServos(T2 / 2, shake_leg1); + MoveServos(T2 / 2, shake_leg2); + + // Shake movement + for (int i = 0; i < numberLegMoves; i++) { + MoveServos(period / (2 * numberLegMoves), shake_leg3); + MoveServos(period / (2 * numberLegMoves), shake_leg2); + } + MoveServos(500, homes); // Return to home position + } + + vTaskDelay(pdMS_TO_TICKS(period)); +} + +//--------------------------------------------------------- +//-- Otto movement: Sit (坐下) +//--------------------------------------------------------- +void Otto::Sit() { + int target[SERVO_COUNT] = {120, 60, 0, 180, 45, 135}; + MoveServos(600, target); +} + +//--------------------------------------------------------- +//-- Otto movement: up & down +//-- Parameters: +//-- * steps: Number of jumps +//-- * T: Period +//-- * h: Jump height: SMALL / MEDIUM / BIG +//-- (or a number in degrees 0 - 90) +//--------------------------------------------------------- +void Otto::UpDown(float steps, int period, int height) { + //-- Both feet are 180 degrees out of phase + //-- Feet amplitude and offset are the same + //-- Initial phase for the right foot is -90, so that it starts + //-- in one extreme position (not in the middle) + int A[SERVO_COUNT] = {0, 0, height, height, 0, 0}; + int O[SERVO_COUNT] = {0, 0, height, -height, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(-90), DEG2RAD(90), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto movement: swinging side to side +//-- Parameters: +//-- steps: Number of steps +//-- T : Period +//-- h : Amount of swing (from 0 to 50 aprox) +//--------------------------------------------------------- +void Otto::Swing(float steps, int period, int height) { + //-- Both feets are in phase. The offset is half the amplitude + //-- It causes the robot to swing from side to side + int A[SERVO_COUNT] = {0, 0, height, height, 0, 0}; + int O[SERVO_COUNT] = { + 0, 0, height / 2, -height / 2, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(0), DEG2RAD(0), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto movement: swinging side to side without touching the floor with the heel +//-- Parameters: +//-- steps: Number of steps +//-- T : Period +//-- h : Amount of swing (from 0 to 50 aprox) +//--------------------------------------------------------- +void Otto::TiptoeSwing(float steps, int period, int height) { + //-- Both feets are in phase. The offset is not half the amplitude in order to tiptoe + //-- It causes the robot to swing from side to side + int A[SERVO_COUNT] = {0, 0, height, height, 0, 0}; + int O[SERVO_COUNT] = {0, 0, height, -height, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Jitter +//-- Parameters: +//-- steps: Number of jitters +//-- T: Period of one jitter +//-- h: height (Values between 5 - 25) +//--------------------------------------------------------- +void Otto::Jitter(float steps, int period, int height) { + //-- Both feet are 180 degrees out of phase + //-- Feet amplitude and offset are the same + //-- Initial phase for the right foot is -90, so that it starts + //-- in one extreme position (not in the middle) + //-- h is constrained to avoid hit the feets + height = std::min(25, height); + int A[SERVO_COUNT] = {height, height, 0, 0, 0, 0}; + int O[SERVO_COUNT] = {0, 0, 0, 0, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {DEG2RAD(-90), DEG2RAD(90), 0, 0, 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Ascending & turn (Jitter while up&down) +//-- Parameters: +//-- steps: Number of bends +//-- T: Period of one bend +//-- h: height (Values between 5 - 15) +//--------------------------------------------------------- +void Otto::AscendingTurn(float steps, int period, int height) { + //-- Both feet and legs are 180 degrees out of phase + //-- Initial phase for the right foot is -90, so that it starts + //-- in one extreme position (not in the middle) + //-- h is constrained to avoid hit the feets + height = std::min(13, height); + int A[SERVO_COUNT] = {height, height, height, height, 0, 0}; + int O[SERVO_COUNT] = { + 0, 0, height + 4, -height + 4, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {DEG2RAD(-90), DEG2RAD(90), DEG2RAD(-90), DEG2RAD(90), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Moonwalker. Otto moves like Michael Jackson +//-- Parameters: +//-- Steps: Number of steps +//-- T: Period +//-- h: Height. Typical valures between 15 and 40 +//-- dir: Direction: LEFT / RIGHT +//--------------------------------------------------------- +void Otto::Moonwalker(float steps, int period, int height, int dir) { + //-- This motion is similar to that of the caterpillar robots: A travelling + //-- wave moving from one side to another + //-- The two Otto's feet are equivalent to a minimal configuration. It is known + //-- that 2 servos can move like a worm if they are 120 degrees out of phase + //-- In the example of Otto, the two feet are mirrored so that we have: + //-- 180 - 120 = 60 degrees. The actual phase difference given to the oscillators + //-- is 60 degrees. + //-- Both amplitudes are equal. The offset is half the amplitud plus a little bit of + //- offset so that the robot tiptoe lightly + + int A[SERVO_COUNT] = {0, 0, height, height, 0, 0}; + int O[SERVO_COUNT] = { + 0, 0, height / 2 + 2, -height / 2 - 2, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + int phi = -dir * 90; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(phi), DEG2RAD(-60 * dir + phi), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//---------------------------------------------------------- +//-- Otto gait: Crusaito. A mixture between moonwalker and walk +//-- Parameters: +//-- steps: Number of steps +//-- T: Period +//-- h: height (Values between 20 - 50) +//-- dir: Direction: LEFT / RIGHT +//----------------------------------------------------------- +void Otto::Crusaito(float steps, int period, int height, int dir) { + int A[SERVO_COUNT] = {25, 25, height, height, 0, 0}; + int O[SERVO_COUNT] = { + 0, 0, height / 2 + 4, -height / 2 - 4, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = {90, 90, DEG2RAD(0), DEG2RAD(-60 * dir), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: Flapping +//-- Parameters: +//-- steps: Number of steps +//-- T: Period +//-- h: height (Values between 10 - 30) +//-- dir: direction: FOREWARD, BACKWARD +//--------------------------------------------------------- +void Otto::Flapping(float steps, int period, int height, int dir) { + int A[SERVO_COUNT] = {12, 12, height, height, 0, 0}; + int O[SERVO_COUNT] = { + 0, 0, height - 10, -height + 10, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + double phase_diff[SERVO_COUNT] = { + DEG2RAD(0), DEG2RAD(180), DEG2RAD(-90 * dir), DEG2RAD(90 * dir), 0, 0}; + + //-- Let's oscillate the servos! + Execute(A, O, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- Otto gait: WhirlwindLeg (旋风腿) +//-- Parameters: +//-- steps: Number of steps +//-- period: Period (建议100-800毫秒) +//-- amplitude: amplitude (Values between 20 - 40) +//--------------------------------------------------------- +void Otto::WhirlwindLeg(float steps, int period, int amplitude) { + + + int target[SERVO_COUNT] = {90, 90, 180, 90, 45, 20}; + MoveServos(100, target); + target[RIGHT_FOOT] = 160; + MoveServos(500, target); + vTaskDelay(pdMS_TO_TICKS(1000)); + + int C[SERVO_COUNT] = {90, 90, 180, 160, 45, 20}; + int A[SERVO_COUNT] = {amplitude, 0, 0, 0, amplitude, 0}; + double phase_diff[SERVO_COUNT] = {DEG2RAD(20), 0, 0, 0, DEG2RAD(20), 0}; + Execute2(A, C, period, phase_diff, steps); + +} + +//--------------------------------------------------------- +//-- 手部动作: 举手 +//-- Parameters: +//-- period: 动作时间 +//-- dir: 方向 1=左手, -1=右手, 0=双手 +//--------------------------------------------------------- +void Otto::HandsUp(int period, int dir) { + if (!has_hands_) { + return; + } + + int target[SERVO_COUNT] = {90, 90, 90, 90, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + + if (dir == 0) { + target[LEFT_HAND] = 170; + target[RIGHT_HAND] = 10; + } else if (dir == LEFT) { + target[LEFT_HAND] = 170; + target[RIGHT_HAND] = servo_[RIGHT_HAND].GetPosition(); + } else if (dir == RIGHT) { + target[RIGHT_HAND] = 10; + target[LEFT_HAND] = servo_[LEFT_HAND].GetPosition(); + } + + MoveServos(period, target); +} + +//--------------------------------------------------------- +//-- 手部动作: 双手放下 +//-- Parameters: +//-- period: 动作时间 +//-- dir: 方向 1=左手, -1=右手, 0=双手 +//--------------------------------------------------------- +void Otto::HandsDown(int period, int dir) { + if (!has_hands_) { + return; + } + + int target[SERVO_COUNT] = {90, 90, 90, 90, HAND_HOME_POSITION, 180 - HAND_HOME_POSITION}; + + if (dir == LEFT) { + target[RIGHT_HAND] = servo_[RIGHT_HAND].GetPosition(); + } else if (dir == RIGHT) { + target[LEFT_HAND] = servo_[LEFT_HAND].GetPosition(); + } + + MoveServos(period, target); +} + +//--------------------------------------------------------- +//-- 手部动作: 挥手 +//-- Parameters: +//-- dir: 方向 LEFT/RIGHT/BOTH +//--------------------------------------------------------- +void Otto::HandWave(int dir) { + if (!has_hands_) { + return; + } + if (dir == LEFT) { + int center_angle[SERVO_COUNT] = {90, 90, 90, 90, 160, 135}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 20, 0}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), 0}; + Execute2(A, center_angle, 300, phase_diff, 5); + } + else if (dir == RIGHT) { + int center_angle[SERVO_COUNT] = {90, 90, 90, 90, 45, 20}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 0, 20}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, 0, DEG2RAD(90)}; + Execute2(A, center_angle, 300, phase_diff, 5); + } + else { + int center_angle[SERVO_COUNT] = {90, 90, 90, 90, 160, 20}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 20, 20}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(90)}; + Execute2(A, center_angle, 300, phase_diff, 5); + } +} + + +//--------------------------------------------------------- +//-- 手部动作: 大风车 +//-- Parameters: +//-- steps: 动作次数 +//-- period: 动作周期(毫秒) +//-- amplitude: 振荡幅度(度) +//--------------------------------------------------------- +void Otto::Windmill(float steps, int period, int amplitude) { + if (!has_hands_) { + return; + } + + int center_angle[SERVO_COUNT] = {90, 90, 90, 90, 90, 90}; + int A[SERVO_COUNT] = {0, 0, 0, 0, amplitude, amplitude}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(90)}; + Execute2(A, center_angle, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- 手部动作: 起飞 +//-- Parameters: +//-- steps: 动作次数 +//-- period: 动作周期(毫秒),数值越小速度越快 +//-- amplitude: 振荡幅度(度) +//--------------------------------------------------------- +void Otto::Takeoff(float steps, int period, int amplitude) { + if (!has_hands_) { + return; + } + + Home(true); + + int center_angle[SERVO_COUNT] = {90, 90, 90, 90, 90, 90}; + int A[SERVO_COUNT] = {0, 0, 0, 0, amplitude, amplitude}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(-90)}; + Execute2(A, center_angle, period, phase_diff, steps); +} + +//--------------------------------------------------------- +//-- 手部动作: 健身 +//-- Parameters: +//-- steps: 动作次数 +//-- period: 动作周期(毫秒) +//-- amplitude: 振荡幅度(度) +//--------------------------------------------------------- +void Otto::Fitness(float steps, int period, int amplitude) { + if (!has_hands_) { + return; + } + int target[SERVO_COUNT] = {90, 90, 90, 0, 160, 135}; + MoveServos(100, target); + target[LEFT_FOOT] = 20; + MoveServos(400, target); + vTaskDelay(pdMS_TO_TICKS(2000)); + + int C[SERVO_COUNT] = {90, 90, 20, 90, 160, 135}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 0, amplitude}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + Execute2(A, C, period, phase_diff, steps); + +} + +//--------------------------------------------------------- +//-- 手部动作: 打招呼 +//-- Parameters: +//-- dir: 方向 LEFT=左手, RIGHT=右手 +//-- steps: 动作次数 +//--------------------------------------------------------- +void Otto::Greeting(int dir, float steps) { + if (!has_hands_) { + return; + } + if (dir == LEFT) { + int target[SERVO_COUNT] = {90, 90, 150, 150, 45, 135}; + MoveServos(400, target); + int C[SERVO_COUNT] = {90, 90, 150, 150, 160, 135}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 20, 0}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + Execute2(A, C, 300, phase_diff, steps); + } + else if (dir == RIGHT) { + int target[SERVO_COUNT] = {90, 90, 30, 30, 45, 135}; + MoveServos(400, target); + int C[SERVO_COUNT] = {90, 90, 30, 30, 45, 20}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 0, 20}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + Execute2(A, C, 300, phase_diff, steps); + } + +} + +//--------------------------------------------------------- +//-- 手部动作: 害羞 +//-- Parameters: +//-- dir: 方向 LEFT=左手, RIGHT=右手 +//-- steps: 动作次数 +//--------------------------------------------------------- +void Otto::Shy(int dir, float steps) { + if (!has_hands_) { + return; + } + + if (dir == LEFT) { + int target[SERVO_COUNT] = {90, 90, 150, 150, 45, 135}; + MoveServos(400, target); + int C[SERVO_COUNT] = {90, 90, 150, 150, 45, 135}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 20, 20}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(-90)}; + Execute2(A, C, 300, phase_diff, steps); + } + else if (dir == RIGHT) { + int target[SERVO_COUNT] = {90, 90, 30, 30, 45, 135}; + MoveServos(400, target); + int C[SERVO_COUNT] = {90, 90, 30, 30, 45, 135}; + int A[SERVO_COUNT] = {0, 0, 0, 0, 0, 20}; + double phase_diff[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(-90)}; + Execute2(A, C, 300, phase_diff, steps); + } +} + +//--------------------------------------------------------- +//-- 手部动作: 广播体操 +//--------------------------------------------------------- +void Otto::RadioCalisthenics() { + if (!has_hands_) { + return; + } + + const int period = 1000; + const float steps = 8.0; + + int C1[SERVO_COUNT] = {90, 90, 90, 90, 145, 45}; + int A1[SERVO_COUNT] = {0, 0, 0, 0, 45, 45}; + double phase_diff1[SERVO_COUNT] = {0, 0, 0, 0, DEG2RAD(90), DEG2RAD(-90)}; + Execute2(A1, C1, period, phase_diff1, steps); + + int C2[SERVO_COUNT] = {90, 90, 115, 65, 90, 90}; + int A2[SERVO_COUNT] = {0, 0, 25, 25, 0, 0}; + double phase_diff2[SERVO_COUNT] = {0, 0, DEG2RAD(90), DEG2RAD(-90), 0, 0}; + Execute2(A2, C2, period, phase_diff2, steps); + + int C3[SERVO_COUNT] = {90, 90, 130, 130, 90, 90}; + int A3[SERVO_COUNT] = {0, 0, 0, 0, 20, 0}; + double phase_diff3[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + Execute2(A3, C3, period, phase_diff3, steps); + + int C4[SERVO_COUNT] = {90, 90, 50, 50, 90, 90}; + int A4[SERVO_COUNT] = {0, 0, 0, 0, 0, 20}; + double phase_diff4[SERVO_COUNT] = {0, 0, 0, 0, 0, 0}; + Execute2(A4, C4, period, phase_diff4, steps); +} + +//--------------------------------------------------------- +//-- 手部动作: 爱的魔力转圈圈 +//--------------------------------------------------------- +void Otto::MagicCircle() { + if (!has_hands_) { + return; + } + + int A[SERVO_COUNT] = {30, 30, 30, 30, 50, 50}; + int O[SERVO_COUNT] = {0, 0, 5, -5, 0, 0}; + double phase_diff[SERVO_COUNT] = {0, 0, DEG2RAD(-90), DEG2RAD(-90), DEG2RAD(-90) , DEG2RAD(90)}; + + Execute(A, O, 700, phase_diff, 40); +} + +//--------------------------------------------------------- +//-- 展示动作:串联多个动作展示 +//--------------------------------------------------------- +void Otto::Showcase() { + if (GetRestState() == true) { + SetRestState(false); + } + + // 1. 往前走3步 + Walk(3, 1000, FORWARD, 50); + vTaskDelay(pdMS_TO_TICKS(500)); + + // 2. 挥挥手 + if (has_hands_) { + HandWave(LEFT); + vTaskDelay(pdMS_TO_TICKS(500)); + } + + // 3. 跳舞(使用广播体操) + if (has_hands_) { + RadioCalisthenics(); + vTaskDelay(pdMS_TO_TICKS(500)); + } + + // 4. 太空步 + Moonwalker(3, 900, 25, LEFT); + vTaskDelay(pdMS_TO_TICKS(500)); + + // 5. 摇摆 + Swing(3, 1000, 30); + vTaskDelay(pdMS_TO_TICKS(500)); + + // 6. 起飞 + if (has_hands_) { + Takeoff(5, 300, 40); + vTaskDelay(pdMS_TO_TICKS(500)); + } + + // 7. 健身 + if (has_hands_) { + Fitness(5, 1000, 25); + vTaskDelay(pdMS_TO_TICKS(500)); + } + + // 8. 往后走3步 + Walk(3, 1000, BACKWARD, 50); +} + +void Otto::EnableServoLimit(int diff_limit) { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].SetLimiter(diff_limit); + } + } +} + +void Otto::DisableServoLimit() { + for (int i = 0; i < SERVO_COUNT; i++) { + if (servo_pins_[i] != -1) { + servo_[i].DisableLimiter(); + } + } +} diff --git a/main/boards/otto-robot/otto_movements.h b/main/boards/otto-robot/otto_movements.h new file mode 100644 index 0000000..69b944e --- /dev/null +++ b/main/boards/otto-robot/otto_movements.h @@ -0,0 +1,117 @@ +#ifndef __OTTO_MOVEMENTS_H__ +#define __OTTO_MOVEMENTS_H__ + +#include "driver/gpio.h" +#include "esp_log.h" +#include "esp_timer.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "oscillator.h" + +//-- Constants +#define FORWARD 1 +#define BACKWARD -1 +#define LEFT 1 +#define RIGHT -1 +#define BOTH 0 +#define SMALL 5 +#define MEDIUM 15 +#define BIG 30 + +// -- Servo delta limit default. degree / sec +#define SERVO_LIMIT_DEFAULT 240 + +// -- Servo indexes for easy access +#define LEFT_LEG 0 +#define RIGHT_LEG 1 +#define LEFT_FOOT 2 +#define RIGHT_FOOT 3 +#define LEFT_HAND 4 +#define RIGHT_HAND 5 +#define SERVO_COUNT 6 + +class Otto { +public: + Otto(); + ~Otto(); + + //-- Otto initialization + void Init(int left_leg, int right_leg, int left_foot, int right_foot, int left_hand = -1, + int right_hand = -1); + //-- Attach & detach functions + void AttachServos(); + void DetachServos(); + + //-- Oscillator Trims + void SetTrims(int left_leg, int right_leg, int left_foot, int right_foot, int left_hand = 0, + int right_hand = 0); + + //-- Predetermined Motion Functions + void MoveServos(int time, int servo_target[]); + void MoveSingle(int position, int servo_number); + void OscillateServos(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float cycle); + void Execute2(int amplitude[SERVO_COUNT], int center_angle[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps); + + //-- HOME = Otto at rest position + void Home(bool hands_down = true); + bool GetRestState(); + void SetRestState(bool state); + + //-- Predetermined Motion Functions + void Jump(float steps = 1, int period = 2000); + + void Walk(float steps = 4, int period = 1000, int dir = FORWARD, int amount = 0); + void Turn(float steps = 4, int period = 2000, int dir = LEFT, int amount = 0); + void Bend(int steps = 1, int period = 1400, int dir = LEFT); + void ShakeLeg(int steps = 1, int period = 2000, int dir = RIGHT); + void Sit(); // 坐下 + + void UpDown(float steps = 1, int period = 1000, int height = 20); + void Swing(float steps = 1, int period = 1000, int height = 20); + void TiptoeSwing(float steps = 1, int period = 900, int height = 20); + void Jitter(float steps = 1, int period = 500, int height = 20); + void AscendingTurn(float steps = 1, int period = 900, int height = 20); + + void Moonwalker(float steps = 1, int period = 900, int height = 20, int dir = LEFT); + void Crusaito(float steps = 1, int period = 900, int height = 20, int dir = FORWARD); + void Flapping(float steps = 1, int period = 1000, int height = 20, int dir = FORWARD); + void WhirlwindLeg(float steps = 1, int period = 300, int amplitude = 30); + + // -- 手部动作 + void HandsUp(int period = 1000, int dir = 0); // 双手举起 + void HandsDown(int period = 1000, int dir = 0); // 双手放下 + void HandWave(int dir = LEFT); // 挥手 + void Windmill(float steps = 10, int period = 500, int amplitude = 90); // 大风车 + void Takeoff(float steps = 5, int period = 300, int amplitude = 40); // 起飞 + void Fitness(float steps = 5, int period = 1000, int amplitude = 25); // 健身 + void Greeting(int dir = LEFT, float steps = 5); // 打招呼 + void Shy(int dir = LEFT, float steps = 5); // 害羞 + void RadioCalisthenics(); // 广播体操 + void MagicCircle(); // 爱的魔力转圈圈 + void Showcase(); // 展示动作(串联多个动作) + + // -- Servo limiter + void EnableServoLimit(int speed_limit_degree_per_sec = SERVO_LIMIT_DEFAULT); + void DisableServoLimit(); + +private: + Oscillator servo_[SERVO_COUNT]; + + int servo_pins_[SERVO_COUNT]; + int servo_trim_[SERVO_COUNT]; + + unsigned long final_time_; + unsigned long partial_time_; + float increment_[SERVO_COUNT]; + + bool is_otto_resting_; + bool has_hands_; // 是否有手部舵机 + + void Execute(int amplitude[SERVO_COUNT], int offset[SERVO_COUNT], int period, + double phase_diff[SERVO_COUNT], float steps); + +}; + +#endif // __OTTO_MOVEMENTS_H__ \ No newline at end of file diff --git a/main/boards/otto-robot/otto_robot.cc b/main/boards/otto-robot/otto_robot.cc new file mode 100644 index 0000000..13f36ce --- /dev/null +++ b/main/boards/otto-robot/otto_robot.cc @@ -0,0 +1,151 @@ +#include +#include +#include +#include +#include +#include +#include + +#include "application.h" +#include "codecs/no_audio_codec.h" +#include "button.h" +#include "config.h" +#include "display/lcd_display.h" +#include "lamp_controller.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "otto_emoji_display.h" +#include "power_manager.h" +#include "system_reset.h" +#include "wifi_board.h" +#include "websocket_control_server.h" + +#define TAG "OttoRobot" + +extern void InitializeOttoController(); + +class OttoRobot : public WifiBoard { +private: + LcdDisplay* display_; + PowerManager* power_manager_; + Button boot_button_; + WebSocketControlServer* ws_control_server_; + void InitializePowerManager() { + power_manager_ = + new PowerManager(POWER_CHARGE_DETECT_PIN, POWER_ADC_UNIT, POWER_ADC_CHANNEL); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new OttoEmojiDisplay( + panel_io, panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeOttoController() { + ESP_LOGI(TAG, "初始化Otto机器人MCP控制器"); + ::InitializeOttoController(); + } + + void InitializeWebSocketControlServer() { + ESP_LOGI(TAG, "初始化WebSocket控制服务器"); + ws_control_server_ = new WebSocketControlServer(); + if (!ws_control_server_->Start(8080)) { + ESP_LOGE(TAG, "Failed to start WebSocket control server"); + delete ws_control_server_; + ws_control_server_ = nullptr; + } else { + ESP_LOGI(TAG, "WebSocket control server started on port 8080"); + } + } + + void StartNetwork() override { + WifiBoard::StartNetwork(); + vTaskDelay(pdMS_TO_TICKS(1000)); + + InitializeWebSocketControlServer(); + } + +public: + OttoRobot() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializePowerManager(); + InitializeOttoController(); + ws_control_server_ = nullptr; + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, + AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, + AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { return display_; } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + charging = power_manager_->IsCharging(); + discharging = !charging; + level = power_manager_->GetBatteryLevel(); + return true; + } +}; + +DECLARE_BOARD(OttoRobot); diff --git a/main/boards/otto-robot/power_manager.h b/main/boards/otto-robot/power_manager.h new file mode 100644 index 0000000..13d8ff3 --- /dev/null +++ b/main/boards/otto-robot/power_manager.h @@ -0,0 +1,128 @@ +#ifndef __POWER_MANAGER_H__ +#define __POWER_MANAGER_H__ + +#include +#include +#include +#include + +class PowerManager { +private: + // 电池电量区间-分压电阻为2个100k + static constexpr struct { + uint16_t adc; + uint8_t level; + } BATTERY_LEVELS[] = {{2150, 0}, {2450, 100}}; + static constexpr size_t BATTERY_LEVELS_COUNT = 2; + static constexpr size_t ADC_VALUES_COUNT = 10; + + esp_timer_handle_t timer_handle_ = nullptr; + gpio_num_t charging_pin_; + adc_unit_t adc_unit_; + adc_channel_t adc_channel_; + uint16_t adc_values_[ADC_VALUES_COUNT]; + size_t adc_values_index_ = 0; + size_t adc_values_count_ = 0; + uint8_t battery_level_ = 100; + bool is_charging_ = false; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + is_charging_ = gpio_get_level(charging_pin_) == 0; + ReadBatteryAdcData(); + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, adc_channel_, &adc_value)); + + adc_values_[adc_values_index_] = adc_value; + adc_values_index_ = (adc_values_index_ + 1) % ADC_VALUES_COUNT; + if (adc_values_count_ < ADC_VALUES_COUNT) { + adc_values_count_++; + } + + uint32_t average_adc = 0; + for (size_t i = 0; i < adc_values_count_; i++) { + average_adc += adc_values_[i]; + } + average_adc /= adc_values_count_; + + CalculateBatteryLevel(average_adc); + + // ESP_LOGI("PowerManager", "ADC值: %d 平均值: %ld 电量: %u%%", adc_value, average_adc, + // battery_level_); + } + + void CalculateBatteryLevel(uint32_t average_adc) { + if (average_adc <= BATTERY_LEVELS[0].adc) { + battery_level_ = 0; + } else if (average_adc >= BATTERY_LEVELS[BATTERY_LEVELS_COUNT - 1].adc) { + battery_level_ = 100; + } else { + float ratio = static_cast(average_adc - BATTERY_LEVELS[0].adc) / + (BATTERY_LEVELS[1].adc - BATTERY_LEVELS[0].adc); + battery_level_ = ratio * 100; + } + } + +public: + PowerManager(gpio_num_t charging_pin, adc_unit_t adc_unit = ADC_UNIT_2, + adc_channel_t adc_channel = ADC_CHANNEL_3) + : charging_pin_(charging_pin), adc_unit_(adc_unit), adc_channel_(adc_channel) { + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + esp_timer_create_args_t timer_args = { + .callback = + [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); // 1秒 + + InitializeAdc(); + } + + void InitializeAdc() { + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = adc_unit_, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, adc_channel_, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { return is_charging_; } + + uint8_t GetBatteryLevel() { return battery_level_; } +}; +#endif // __POWER_MANAGER_H__ \ No newline at end of file diff --git a/main/boards/otto-robot/websocket_control_server.cc b/main/boards/otto-robot/websocket_control_server.cc new file mode 100644 index 0000000..a38944b --- /dev/null +++ b/main/boards/otto-robot/websocket_control_server.cc @@ -0,0 +1,191 @@ +#include "websocket_control_server.h" +#include "mcp_server.h" +#include +#include +#include +#include +#include +#include + +static const char* TAG = "WSControl"; + +WebSocketControlServer* WebSocketControlServer::instance_ = nullptr; + +WebSocketControlServer::WebSocketControlServer() : server_handle_(nullptr) { + instance_ = this; +} + +WebSocketControlServer::~WebSocketControlServer() { + Stop(); + instance_ = nullptr; +} + +esp_err_t WebSocketControlServer::ws_handler(httpd_req_t *req) { + if (instance_ == nullptr) { + return ESP_FAIL; + } + + if (req->method == HTTP_GET) { + ESP_LOGI(TAG, "Handshake done, the new connection was opened"); + instance_->AddClient(req); + return ESP_OK; + } + + httpd_ws_frame_t ws_pkt; + uint8_t *buf = NULL; + memset(&ws_pkt, 0, sizeof(httpd_ws_frame_t)); + ws_pkt.type = HTTPD_WS_TYPE_TEXT; + + /* Set max_len = 0 to get the frame len */ + esp_err_t ret = httpd_ws_recv_frame(req, &ws_pkt, 0); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "httpd_ws_recv_frame failed to get frame len with %d", ret); + return ret; + } + ESP_LOGI(TAG, "frame len is %d", ws_pkt.len); + + if (ws_pkt.len) { + /* ws_pkt.len + 1 is for NULL termination as we are expecting a string */ + buf = (uint8_t*)calloc(1, ws_pkt.len + 1); + if (buf == NULL) { + ESP_LOGE(TAG, "Failed to calloc memory for buf"); + return ESP_ERR_NO_MEM; + } + ws_pkt.payload = buf; + /* Set max_len = ws_pkt.len to get the frame payload */ + ret = httpd_ws_recv_frame(req, &ws_pkt, ws_pkt.len); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "httpd_ws_recv_frame failed with %d", ret); + free(buf); + return ret; + } + ESP_LOGI(TAG, "Got packet with message: %s", ws_pkt.payload); + } + + ESP_LOGI(TAG, "Packet type: %d", ws_pkt.type); + + if (ws_pkt.type == HTTPD_WS_TYPE_CLOSE) { + ESP_LOGI(TAG, "WebSocket close frame received"); + instance_->RemoveClient(req); + free(buf); + return ESP_OK; + } + + if (ws_pkt.type == HTTPD_WS_TYPE_TEXT) { + if (ws_pkt.len > 0 && buf != nullptr) { + buf[ws_pkt.len] = '\0'; + instance_->HandleMessage(req, (const char*)buf, ws_pkt.len); + } + } else { + ESP_LOGW(TAG, "Unsupported frame type: %d", ws_pkt.type); + } + + free(buf); + return ESP_OK; +} + +bool WebSocketControlServer::Start(int port) { + httpd_config_t config = HTTPD_DEFAULT_CONFIG(); + config.server_port = port; + config.max_open_sockets = 7; + + httpd_uri_t ws_uri = { + .uri = "/ws", + .method = HTTP_GET, + .handler = ws_handler, + .user_ctx = nullptr, + .is_websocket = true + }; + + if (httpd_start(&server_handle_, &config) == ESP_OK) { + httpd_register_uri_handler(server_handle_, &ws_uri); + ESP_LOGI(TAG, "WebSocket server started on port %d", port); + return true; + } + + ESP_LOGE(TAG, "Failed to start WebSocket server"); + return false; +} + +void WebSocketControlServer::Stop() { + if (server_handle_) { + httpd_stop(server_handle_); + server_handle_ = nullptr; + clients_.clear(); + ESP_LOGI(TAG, "WebSocket server stopped"); + } +} + +void WebSocketControlServer::HandleMessage(httpd_req_t *req, const char* data, size_t len) { + if (data == nullptr || len == 0) { + ESP_LOGE(TAG, "Invalid message: data is null or len is 0"); + return; + } + + if (len > 4096) { + ESP_LOGE(TAG, "Message too long: %zu bytes", len); + return; + } + + char* temp_buf = (char*)malloc(len + 1); + if (temp_buf == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory"); + return; + } + memcpy(temp_buf, data, len); + temp_buf[len] = '\0'; + + cJSON* root = cJSON_Parse(temp_buf); + free(temp_buf); + + if (root == nullptr) { + ESP_LOGE(TAG, "Failed to parse JSON"); + return; + } + + // 支持两种格式: + // 1. 完整格式:{"type":"mcp","payload":{...}} + // 2. 简化格式:直接是MCP payload对象 + + cJSON* payload = nullptr; + cJSON* type = cJSON_GetObjectItem(root, "type"); + + if (type && cJSON_IsString(type) && strcmp(type->valuestring, "mcp") == 0) { + payload = cJSON_GetObjectItem(root, "payload"); + if (payload != nullptr) { + cJSON_DetachItemViaPointer(root, payload); + McpServer::GetInstance().ParseMessage(payload); + cJSON_Delete(payload); + } + } else { + payload = cJSON_Duplicate(root, 1); + if (payload != nullptr) { + McpServer::GetInstance().ParseMessage(payload); + cJSON_Delete(payload); + } + } + + if (payload == nullptr) { + ESP_LOGE(TAG, "Invalid message format or failed to parse"); + } + + cJSON_Delete(root); +} + +void WebSocketControlServer::AddClient(httpd_req_t *req) { + int sock_fd = httpd_req_to_sockfd(req); + if (clients_.find(sock_fd) == clients_.end()) { + clients_[sock_fd] = req; + ESP_LOGI(TAG, "Client connected: %d (total: %zu)", sock_fd, clients_.size()); + } +} + +void WebSocketControlServer::RemoveClient(httpd_req_t *req) { + int sock_fd = httpd_req_to_sockfd(req); + clients_.erase(sock_fd); + ESP_LOGI(TAG, "Client disconnected: %d (total: %zu)", sock_fd, clients_.size()); +} + +size_t WebSocketControlServer::GetClientCount() const { + return clients_.size(); +} diff --git a/main/boards/otto-robot/websocket_control_server.h b/main/boards/otto-robot/websocket_control_server.h new file mode 100644 index 0000000..f8e5e41 --- /dev/null +++ b/main/boards/otto-robot/websocket_control_server.h @@ -0,0 +1,33 @@ +#ifndef WEBSOCKET_CONTROL_SERVER_H +#define WEBSOCKET_CONTROL_SERVER_H + +#include +#include +#include +#include + +class WebSocketControlServer { +public: + WebSocketControlServer(); + ~WebSocketControlServer(); + + bool Start(int port = 8080); + + void Stop(); + + size_t GetClientCount() const; + +private: + httpd_handle_t server_handle_; + std::map clients_; + + static esp_err_t ws_handler(httpd_req_t *req); + + void HandleMessage(httpd_req_t *req, const char* data, size_t len); + void AddClient(httpd_req_t *req); + void RemoveClient(httpd_req_t *req); + static WebSocketControlServer* instance_; +}; + +#endif // WEBSOCKET_CONTROL_SERVER_H + diff --git a/main/boards/sensecap-watcher/README.md b/main/boards/sensecap-watcher/README.md new file mode 100644 index 0000000..aa91010 --- /dev/null +++ b/main/boards/sensecap-watcher/README.md @@ -0,0 +1,52 @@ +# 编译命令 + +## 一键编译 + +```bash +python scripts/release.py sensecap-watcher +``` + +## 手动配置编译 + +```bash +idf.py set-target esp32s3 +``` + +**配置** + +```bash +idf.py menuconfig +``` + +选择板子 + +``` +Xiaozhi Assistant -> Board Type -> SenseCAP Watcher +``` + +watcher 中一些额外的配置项如下,需要在menuconfig 中选择. + +``` +CONFIG_BOARD_TYPE_SEEED_STUDIO_SENSECAP_WATCHER=y +CONFIG_ESPTOOLPY_FLASHSIZE_32MB=y +CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions/v2/32m.csv" +CONFIG_BOOTLOADER_CACHE_32BIT_ADDR_QUAD_FLASH=y +CONFIG_ESPTOOLPY_FLASH_MODE_AUTO_DETECT=n +CONFIG_IDF_EXPERIMENTAL_FEATURES=y +``` + +## 编译烧入 + +```bash +idf.py -DBOARD_NAME=sensecap-watcher build flash +``` + +注意: 如果当前设备出货之前是SenseCAP 固件(非小智版本),请特别小心处理闪存固件分区地址,以避免错误擦除 SenseCAP Watcher 的自身设备信息(EUI 等),否则设备即使恢复成SenseCAP固件也无法正确连接到 SenseCraft 服务器!所以在刷写固件之前,请务必记录设备的相关必要信息,以确保有恢复的方法! + +您可以使用以下命令备份生产信息 + +```bash +# firstly backup the factory information partition which contains the credentials for connecting the SenseCraft server +esptool.py --chip esp32s3 --baud 2000000 --before default_reset --after hard_reset --no-stub read_flash 0x9000 204800 nvsfactory.bin + +``` \ No newline at end of file diff --git a/main/boards/sensecap-watcher/README_en.md b/main/boards/sensecap-watcher/README_en.md new file mode 100644 index 0000000..27338a8 --- /dev/null +++ b/main/boards/sensecap-watcher/README_en.md @@ -0,0 +1,53 @@ +# Build Instructions + +## One-click Build + +```bash +python scripts/release.py sensecap-watcher -c config_en.json +``` + +## Manual Configuration and Build + +```bash +idf.py set-target esp32s3 +``` + +**Configuration** + +```bash +idf.py menuconfig +``` + +Select the board: + +``` +Xiaozhi Assistant -> Board Type -> SenseCAP Watcher +``` + +There are some additional configuration options for the watcher. Please select them in menuconfig: + +``` +CONFIG_BOARD_TYPE_SEEED_STUDIO_SENSECAP_WATCHER=y +CONFIG_ESPTOOLPY_FLASHSIZE_32MB=y +CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions/v2/32m.csv" +CONFIG_BOOTLOADER_CACHE_32BIT_ADDR_QUAD_FLASH=y +CONFIG_ESPTOOLPY_FLASH_MODE_AUTO_DETECT=n +CONFIG_IDF_EXPERIMENTAL_FEATURES=y +CONFIG_LANGUAGE_EN_US=y +CONFIG_SR_WN_WN9_JARVIS_TTS=y +``` + +## Build and Flash + +```bash +idf.py -DBOARD_NAME=sensecap-watcher-en build flash +``` + +Note: If your device was previously shipped with the SenseCAP firmware (not the Xiaozhi version), please be very careful with the flash partition addresses to avoid accidentally erasing the device information (such as EUI) of the SenseCAP Watcher. Otherwise, even if you restore the SenseCAP firmware, the device may not be able to connect to the SenseCraft server correctly! Therefore, before flashing the firmware, be sure to record the necessary device information to ensure you have a way to recover it! + +You can use the following command to back up the factory information: + +```bash +# Firstly backup the factory information partition which contains the credentials for connecting the SenseCraft server +esptool.py --chip esp32s3 --baud 2000000 --before default_reset --after hard_reset --no-stub read_flash 0x9000 204800 nvsfactory.bin +``` diff --git a/main/boards/sensecap-watcher/config.h b/main/boards/sensecap-watcher/config.h new file mode 100644 index 0000000..8d1f5dc --- /dev/null +++ b/main/boards/sensecap-watcher/config.h @@ -0,0 +1,152 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include "driver/spi_common.h" +#include "esp_io_expander.h" + +// SSCMA Client Configuration +#define CONFIG_SSCMA_EVENT_QUEUE_SIZE 1 +#define CONFIG_SSCMA_TX_BUFFER_SIZE 8192 +#define CONFIG_SSCMA_RX_BUFFER_SIZE 98304 + +// SSCMA Client Process Task +#define CONFIG_SSCMA_PROCESS_TASK_STACK_SIZE 10240 +#define CONFIG_SSCMA_PROCESS_TASK_PRIORITY 5 +#define CONFIG_SSCMA_PROCESS_TASK_AFFINITY_CPU1 1 +#define CONFIG_SSCMA_PROCESS_TASK_AFFINITY 1 +#define CONFIG_SSCMA_PROCESS_TASK_STACK_ALLOC_EXTERNAL 1 + +// SSCMA Client Monitor Task +#define CONFIG_SSCMA_MONITOR_TASK_STACK_SIZE 10240 +#define CONFIG_SSCMA_MONITOR_TASK_PRIORITY 4 +#define CONFIG_SSCMA_MONITOR_TASK_AFFINITY_CPU1 1 +#define CONFIG_SSCMA_MONITOR_TASK_AFFINITY 1 +#define CONFIG_SSCMA_MONITOR_TASK_STACK_ALLOC_EXTERNAL 1 +#define CONFIG_SSCMA_ALLOC_SMALL_SHORTTERM_MEM_EXTERNALLY 1 + +/* General I2C */ +#define BSP_GENERAL_I2C_NUM (I2C_NUM_0) +#define BSP_GENERAL_I2C_SDA (GPIO_NUM_47) +#define BSP_GENERAL_I2C_SCL (GPIO_NUM_48) + +/* Audio */ +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE false + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_16 + + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7243E_ADDR (0x14) + + + +#define BUILTIN_LED_GPIO GPIO_NUM_40 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +/* Expander */ +#define BSP_IO_EXPANDER_INT (GPIO_NUM_2) +#define DRV_IO_EXP_INPUT_MASK (0x20ff) // P0.0 ~ P0.7 | P1.3 +#define DRV_IO_EXP_OUTPUT_MASK (0xDf00) // P1.0 ~ P1.7 & ~P1.3 + +/* Expander IO PIN */ +#define BSP_PWR_CHRG_DET (IO_EXPANDER_PIN_NUM_0) +#define BSP_PWR_STDBY_DET (IO_EXPANDER_PIN_NUM_1) +#define BSP_PWR_VBUS_IN_DET (IO_EXPANDER_PIN_NUM_2) +#define BSP_PWR_SDCARD (IO_EXPANDER_PIN_NUM_8) +#define BSP_PWR_LCD (IO_EXPANDER_PIN_NUM_9) +#define BSP_PWR_SYSTEM (IO_EXPANDER_PIN_NUM_10) +#define BSP_PWR_AI_CHIP (IO_EXPANDER_PIN_NUM_11) +#define BSP_PWR_CODEC_PA (IO_EXPANDER_PIN_NUM_12) +#define BSP_PWR_BAT_DET (IO_EXPANDER_PIN_NUM_13) +#define BSP_PWR_GROVE (IO_EXPANDER_PIN_NUM_14) +#define BSP_PWR_BAT_ADC (IO_EXPANDER_PIN_NUM_15) + +#define BSP_PWR_START_UP (BSP_PWR_SDCARD | BSP_PWR_LCD | BSP_PWR_SYSTEM | BSP_PWR_AI_CHIP | BSP_PWR_CODEC_PA | BSP_PWR_GROVE | BSP_PWR_BAT_ADC) + +#define BSP_KNOB_BTN (IO_EXPANDER_PIN_NUM_3) +#define BSP_KNOB_A_PIN GPIO_NUM_41 +#define BSP_KNOB_B_PIN GPIO_NUM_42 + +/* SPI */ +#define BSP_SPI2_HOST_SCLK (GPIO_NUM_4) +#define BSP_SPI2_HOST_MOSI (GPIO_NUM_5) +#define BSP_SPI2_HOST_MISO (GPIO_NUM_6) + +/* SD Card */ +#define BSP_SD_SPI_NUM (SPI2_HOST) +#define BSP_SD_SPI_CS (GPIO_NUM_46) +#define BSP_SD_GPIO_DET (IO_EXPANDER_PIN_NUM_4) + +/* QSPI */ +#define BSP_SPI3_HOST_PCLK (GPIO_NUM_7) +#define BSP_SPI3_HOST_DATA0 (GPIO_NUM_9) +#define BSP_SPI3_HOST_DATA1 (GPIO_NUM_1) +#define BSP_SPI3_HOST_DATA2 (GPIO_NUM_14) +#define BSP_SPI3_HOST_DATA3 (GPIO_NUM_13) + +/* LCD */ +#define BSP_LCD_SPI_NUM (SPI3_HOST) +#define BSP_LCD_SPI_CS (GPIO_NUM_45) +#define BSP_LCD_GPIO_RST (GPIO_NUM_NC) +#define BSP_LCD_GPIO_DC (GPIO_NUM_1) + +#define DISPLAY_WIDTH 412 +#define DISPLAY_HEIGHT 412 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_8 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +/* Touch */ +#define BSP_TOUCH_I2C_NUM (1) +#define BSP_TOUCH_GPIO_INT (IO_EXPANDER_PIN_NUM_5) +#define BSP_TOUCH_I2C_SDA (GPIO_NUM_39) +#define BSP_TOUCH_I2C_SCL (GPIO_NUM_38) +#define BSP_TOUCH_I2C_CLK (400000) + +/* Settings */ +#define DRV_LCD_PIXEL_CLK_HZ (40 * 1000 * 1000) +#define DRV_LCD_CMD_BITS (32) +#define DRV_LCD_PARAM_BITS (8) +#define DRV_LCD_RGB_ELEMENT_ORDER (LCD_RGB_ELEMENT_ORDER_RGB) +#define DRV_LCD_BITS_PER_PIXEL (16) + +#define CONFIG_BSP_LCD_SPI_DMA_SIZE_DIV 16 + +/* ADC */ +#define BSP_BAT_ADC_CHAN (ADC_CHANNEL_2) // GPIO3 +#define BSP_BAT_ADC_ATTEN (ADC_ATTEN_DB_2_5) // 0 ~ 1100 mV +#define BSP_BAT_VOL_RATIO ((62 + 20) / 20) + +/* Himax */ +#define BSP_SSCMA_CLIENT_RST (IO_EXPANDER_PIN_NUM_7) +#define BSP_SSCMA_CLIENT_RST_USE_EXPANDER (true) + +#define BSP_SSCMA_CLIENT_SPI_NUM (SPI2_HOST) +#define BSP_SSCMA_CLIENT_SPI_CS (GPIO_NUM_21) +#define BSP_SSCMA_CLIENT_SPI_SYNC (IO_EXPANDER_PIN_NUM_6) +#define BSP_SSCMA_CLIENT_SPI_SYNC_USE_EXPANDER (true) +#define BSP_SSCMA_CLIENT_SPI_CLK (12 * 1000 * 1000) + +#define BSP_SSCMA_FLASHER_UART_NUM (UART_NUM_1) +#define BSP_SSCMA_FLASHER_UART_TX (GPIO_NUM_17) +#define BSP_SSCMA_FLASHER_UART_RX (GPIO_NUM_18) +#define BSP_SSCMA_FLASHER_UART_BAUD_RATE (921600) + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/sensecap-watcher/config.json b/main/boards/sensecap-watcher/config.json new file mode 100644 index 0000000..177fad7 --- /dev/null +++ b/main/boards/sensecap-watcher/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "sensecap-watcher", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_32MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/32m.csv\"", + "CONFIG_BOOTLOADER_CACHE_32BIT_ADDR_QUAD_FLASH=y", + "CONFIG_ESPTOOLPY_FLASH_MODE_AUTO_DETECT=n", + "CONFIG_IDF_EXPERIMENTAL_FEATURES=y", + "CONFIG_FREERTOS_HZ=1000" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/sensecap-watcher/config_en.json b/main/boards/sensecap-watcher/config_en.json new file mode 100644 index 0000000..0435fa3 --- /dev/null +++ b/main/boards/sensecap-watcher/config_en.json @@ -0,0 +1,20 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "sensecap-watcher-en", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_32MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/32m.csv\"", + "CONFIG_BOOTLOADER_CACHE_32BIT_ADDR_QUAD_FLASH=y", + "CONFIG_ESPTOOLPY_FLASH_MODE_AUTO_DETECT=n", + "CONFIG_IDF_EXPERIMENTAL_FEATURES=y", + "CONFIG_FREERTOS_HZ=1000", + "CONFIG_LANGUAGE_EN_US=y", + "CONFIG_SR_WN_WN9_JARVIS_TTS=y", + "CONFIG_SR_WN_WN9_SOPHIA_TTS=y", + "CONFIG_SR_WN_WN9_NIHAOXIAOZHI_TTS=n" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/sensecap-watcher/sensecap_audio_codec.cc b/main/boards/sensecap-watcher/sensecap_audio_codec.cc new file mode 100644 index 0000000..ac474d7 --- /dev/null +++ b/main/boards/sensecap-watcher/sensecap_audio_codec.cc @@ -0,0 +1,214 @@ +#include "sensecap_audio_codec.h" + +#include +#include +#include + +static const char TAG[] = "SensecapAudioCodec"; + +SensecapAudioCodec::SensecapAudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7243e_addr, bool input_reference) { + duplex_ = true; // 是否双工 + input_reference_ = input_reference; // 是否使用参考输入,实现回声消除 + input_channels_ = input_reference_ ? 2 : 1; // 输入通道数 + input_sample_rate_ = input_sample_rate; + output_sample_rate_ = output_sample_rate; + + CreateDuplexChannels(mclk, bclk, ws, dout, din); + + // Do initialize of related interface: data_if, ctrl_if and gpio_if + audio_codec_i2s_cfg_t i2s_cfg = { + .port = I2S_NUM_0, + .rx_handle = rx_handle_, + .tx_handle = tx_handle_, + }; + data_if_ = audio_codec_new_i2s_data(&i2s_cfg); + assert(data_if_ != NULL); + + // Output + audio_codec_i2c_cfg_t i2c_cfg = { + .port = (i2c_port_t)0, + .addr = es8311_addr, + .bus_handle = i2c_master_handle, + }; + out_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(out_ctrl_if_ != NULL); + + gpio_if_ = audio_codec_new_gpio(); + assert(gpio_if_ != NULL); + + es8311_codec_cfg_t es8311_cfg = {}; + es8311_cfg.ctrl_if = out_ctrl_if_; + es8311_cfg.gpio_if = gpio_if_; + es8311_cfg.codec_mode = ESP_CODEC_DEV_WORK_MODE_DAC; + es8311_cfg.pa_pin = pa_pin; + es8311_cfg.use_mclk = true; + es8311_cfg.hw_gain.pa_voltage = 5.0; + es8311_cfg.hw_gain.codec_dac_voltage = 3.3; + out_codec_if_ = es8311_codec_new(&es8311_cfg); + assert(out_codec_if_ != NULL); + + esp_codec_dev_cfg_t dev_cfg = { + .dev_type = ESP_CODEC_DEV_TYPE_OUT, + .codec_if = out_codec_if_, + .data_if = data_if_, + }; + output_dev_ = esp_codec_dev_new(&dev_cfg); + assert(output_dev_ != NULL); + + // Input + i2c_cfg.addr = es7243e_addr << 1; + in_ctrl_if_ = audio_codec_new_i2c_ctrl(&i2c_cfg); + assert(in_ctrl_if_ != NULL); + + es7243e_codec_cfg_t es7243e_cfg = {}; + es7243e_cfg.ctrl_if = in_ctrl_if_; + in_codec_if_ = es7243e_codec_new(&es7243e_cfg); + assert(in_codec_if_ != NULL); + + dev_cfg.dev_type = ESP_CODEC_DEV_TYPE_IN; + dev_cfg.codec_if = in_codec_if_; + input_dev_ = esp_codec_dev_new(&dev_cfg); + assert(input_dev_ != NULL); + + esp_codec_set_disable_when_closed(output_dev_, false); + esp_codec_set_disable_when_closed(input_dev_, false); + + ESP_LOGI(TAG, "SensecapAudioDevice initialized"); +} + +SensecapAudioCodec::~SensecapAudioCodec() { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + esp_codec_dev_delete(output_dev_); + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + esp_codec_dev_delete(input_dev_); + + audio_codec_delete_codec_if(in_codec_if_); + audio_codec_delete_ctrl_if(in_ctrl_if_); + audio_codec_delete_codec_if(out_codec_if_); + audio_codec_delete_ctrl_if(out_ctrl_if_); + audio_codec_delete_gpio_if(gpio_if_); + audio_codec_delete_data_if(data_if_); +} + +void SensecapAudioCodec::CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din) { + assert(input_sample_rate_ == output_sample_rate_); + + i2s_chan_config_t chan_cfg = { + .id = I2S_NUM_0, + .role = I2S_ROLE_MASTER, + .dma_desc_num = AUDIO_CODEC_DMA_DESC_NUM, + .dma_frame_num = AUDIO_CODEC_DMA_FRAME_NUM, + .auto_clear_after_cb = true, + .auto_clear_before_cb = false, + .intr_priority = 0, + }; + ESP_ERROR_CHECK(i2s_new_channel(&chan_cfg, &tx_handle_, &rx_handle_)); + + i2s_std_config_t std_cfg = { + .clk_cfg = { + .sample_rate_hz = (uint32_t)output_sample_rate_, + .clk_src = I2S_CLK_SRC_DEFAULT, + .ext_clk_freq_hz = 0, + .mclk_multiple = I2S_MCLK_MULTIPLE_256 + }, + .slot_cfg = { + .data_bit_width = I2S_DATA_BIT_WIDTH_16BIT, + .slot_bit_width = I2S_SLOT_BIT_WIDTH_AUTO, + .slot_mode = I2S_SLOT_MODE_MONO, + .slot_mask = I2S_STD_SLOT_BOTH, + .ws_width = I2S_DATA_BIT_WIDTH_16BIT, + .ws_pol = false, + .bit_shift = true, + .left_align = true, + .big_endian = false, + .bit_order_lsb = false + }, + .gpio_cfg = { + .mclk = mclk, + .bclk = bclk, + .ws = ws, + .dout = dout, + .din = din, + .invert_flags = { + .mclk_inv = false, + .bclk_inv = false, + .ws_inv = false + } + } + }; + + ESP_ERROR_CHECK(i2s_channel_init_std_mode(tx_handle_, &std_cfg)); + + std_cfg.slot_cfg.slot_mask = I2S_STD_SLOT_RIGHT; + ESP_ERROR_CHECK(i2s_channel_init_std_mode(rx_handle_, &std_cfg)); + ESP_LOGI(TAG, "Duplex channels created"); +} + +void SensecapAudioCodec::SetOutputVolume(int volume) { + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, volume)); + AudioCodec::SetOutputVolume(volume); +} + +void SensecapAudioCodec::EnableInput(bool enable) { + if (enable == input_enabled_) { + return; + } + if (enable) { + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 2, + .channel_mask = ESP_CODEC_DEV_MAKE_CHANNEL_MASK(1), + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(input_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_in_gain(input_dev_, 27.0)); + } else { + ESP_ERROR_CHECK(esp_codec_dev_close(input_dev_)); + } + AudioCodec::EnableInput(enable); +} + +void SensecapAudioCodec::EnableOutput(bool enable) { + if (enable == output_enabled_) { + return; + } + if (enable) { + // Play 16bit 1 channel + esp_codec_dev_sample_info_t fs = { + .bits_per_sample = 16, + .channel = 1, + .channel_mask = 0, + .sample_rate = (uint32_t)output_sample_rate_, + .mclk_multiple = 0, + }; + ESP_ERROR_CHECK(esp_codec_dev_open(output_dev_, &fs)); + ESP_ERROR_CHECK(esp_codec_dev_set_out_vol(output_dev_, output_volume_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 1); + } + } + else { + ESP_ERROR_CHECK(esp_codec_dev_close(output_dev_)); + if (pa_pin_ != GPIO_NUM_NC) { + gpio_set_level(pa_pin_, 0); + } + } + AudioCodec::EnableOutput(enable); +} + +int SensecapAudioCodec::Read(int16_t* dest, int samples) { + if (input_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_read(input_dev_, (void*)dest, samples * sizeof(int16_t))); + } + return samples; +} + +int SensecapAudioCodec::Write(const int16_t* data, int samples) { + if (output_enabled_) { + ESP_ERROR_CHECK_WITHOUT_ABORT(esp_codec_dev_write(output_dev_, (void*)data, samples * sizeof(int16_t))); + } + return samples; +} \ No newline at end of file diff --git a/main/boards/sensecap-watcher/sensecap_audio_codec.h b/main/boards/sensecap-watcher/sensecap_audio_codec.h new file mode 100644 index 0000000..794a4d7 --- /dev/null +++ b/main/boards/sensecap-watcher/sensecap_audio_codec.h @@ -0,0 +1,38 @@ +#ifndef _SENSECAP_AUDIO_CODEC_H +#define _SENSECAP_AUDIO_CODEC_H + +#include "audio_codec.h" + +#include +#include + +class SensecapAudioCodec : public AudioCodec { +private: + const audio_codec_data_if_t* data_if_ = nullptr; + const audio_codec_ctrl_if_t* out_ctrl_if_ = nullptr; + const audio_codec_if_t* out_codec_if_ = nullptr; + const audio_codec_ctrl_if_t* in_ctrl_if_ = nullptr; + const audio_codec_if_t* in_codec_if_ = nullptr; + const audio_codec_gpio_if_t* gpio_if_ = nullptr; + + esp_codec_dev_handle_t output_dev_ = nullptr; + esp_codec_dev_handle_t input_dev_ = nullptr; + gpio_num_t pa_pin_ = GPIO_NUM_NC; + + void CreateDuplexChannels(gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din); + + virtual int Read(int16_t* dest, int samples) override; + virtual int Write(const int16_t* data, int samples) override; + +public: + SensecapAudioCodec(void* i2c_master_handle, int input_sample_rate, int output_sample_rate, + gpio_num_t mclk, gpio_num_t bclk, gpio_num_t ws, gpio_num_t dout, gpio_num_t din, + gpio_num_t pa_pin, uint8_t es8311_addr, uint8_t es7210_addr, bool input_reference); + virtual ~SensecapAudioCodec(); + + virtual void SetOutputVolume(int volume) override; + virtual void EnableInput(bool enable) override; + virtual void EnableOutput(bool enable) override; +}; + +#endif // _SENSECAP_AUDIO_CODEC_H diff --git a/main/boards/sensecap-watcher/sensecap_watcher.cc b/main/boards/sensecap-watcher/sensecap_watcher.cc new file mode 100644 index 0000000..c6a00dd --- /dev/null +++ b/main/boards/sensecap-watcher/sensecap_watcher.cc @@ -0,0 +1,660 @@ +#include "display/lv_display.h" +#include "misc/lv_event.h" +#include "wifi_board.h" +#include "sensecap_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "knob.h" +#include "config.h" +#include "led/single_led.h" +#include "power_save_timer.h" +#include "sscma_camera.h" +#include "lvgl_theme.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "assets/lang_config.h" + +#define TAG "sensecap_watcher" + +class CustomLcdDisplay : public SpiLcdDisplay { + public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + + lv_obj_set_size(top_bar_, LV_HOR_RES, text_font->line_height); + lv_obj_set_style_layout(top_bar_, LV_LAYOUT_NONE, 0); + lv_obj_set_style_pad_top(top_bar_, 10, 0); + lv_obj_set_style_pad_bottom(top_bar_, 1, 0); + + lv_obj_set_size(status_bar_, LV_HOR_RES, text_font->line_height); + lv_obj_set_style_layout(status_bar_, LV_LAYOUT_NONE, 0); + lv_obj_set_style_pad_top(status_bar_, 10, 0); + lv_obj_set_style_pad_bottom(status_bar_, 1, 0); + lv_obj_set_y(status_bar_, text_font->line_height); + lv_obj_add_flag(status_bar_, LV_OBJ_FLAG_IGNORE_LAYOUT); + + // Reparent mute and battery labels to top_bar_ to allow absolute positioning + lv_obj_set_parent(mute_label_, top_bar_); + lv_obj_set_parent(battery_label_, top_bar_); + lv_obj_set_style_margin_left(battery_label_, 0, 0); + + // 针对圆形屏幕调整位置 + // network mute battery // + // status // + lv_obj_align(network_label_, LV_ALIGN_TOP_MID, -1.5 * icon_font->line_height, 0); + lv_obj_align(mute_label_, LV_ALIGN_TOP_MID, 1.0 * icon_font->line_height, 0); + lv_obj_align(battery_label_, LV_ALIGN_TOP_MID, 2.5 * icon_font->line_height, 0); + + lv_obj_align(status_label_, LV_ALIGN_BOTTOM_MID, 0, 0); + lv_obj_set_flex_grow(status_label_, 0); + lv_obj_set_width(status_label_, LV_HOR_RES * 0.75); + lv_label_set_long_mode(status_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + + lv_obj_align(notification_label_, LV_ALIGN_BOTTOM_MID, 0, 0); + lv_obj_set_width(notification_label_, LV_HOR_RES * 0.75); + lv_label_set_long_mode(notification_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + + lv_obj_align(low_battery_popup_, LV_ALIGN_BOTTOM_MID, 0, -20); + lv_obj_set_style_bg_color(low_battery_popup_, lv_color_hex(0xFF0000), 0); + lv_obj_set_width(low_battery_label_, LV_HOR_RES * 0.75); + lv_label_set_long_mode(low_battery_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + + // 针对圆形屏幕调整底部对话框位置,避免被圆角遮挡 + lv_obj_set_style_pad_bottom(bottom_bar_, 30, 0); + lv_obj_set_width(chat_message_label_, LV_HOR_RES * 0.75); // 限制宽度,避免文字贴边 + } +}; + +class SensecapWatcher : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + LcdDisplay* display_; + std::unique_ptr knob_; + esp_io_expander_handle_t io_exp_handle; + button_handle_t btns; + PowerSaveTimer* power_save_timer_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + uint32_t long_press_cnt_; + button_driver_t* btn_driver_ = nullptr; + static SensecapWatcher* instance_; + SscmaCamera* camera_ = nullptr; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + bool is_charging = (IoExpanderGetLevel(BSP_PWR_VBUS_IN_DET) == 0); + if (is_charging) { + ESP_LOGI(TAG, "charging"); + GetBacklight()->SetBrightness(0); + } else { + IoExpanderSetLevel(BSP_PWR_SYSTEM, 0); + } + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = BSP_GENERAL_I2C_SDA, + .scl_io_num = BSP_GENERAL_I2C_SCL, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + + // pulldown for lcd i2c + const gpio_config_t io_config = { + .pin_bit_mask = (1ULL << BSP_TOUCH_I2C_SDA) | (1ULL << BSP_TOUCH_I2C_SCL) | (1ULL << BSP_SPI3_HOST_PCLK) | (1ULL << BSP_SPI3_HOST_DATA0) | (1ULL << BSP_SPI3_HOST_DATA1) + | (1ULL << BSP_SPI3_HOST_DATA2) | (1ULL << BSP_SPI3_HOST_DATA3) | (1ULL << BSP_LCD_SPI_CS) | (1UL << DISPLAY_BACKLIGHT_PIN), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + gpio_config(&io_config); + + gpio_set_level(BSP_TOUCH_I2C_SDA, 0); + gpio_set_level(BSP_TOUCH_I2C_SCL, 0); + + gpio_set_level(BSP_LCD_SPI_CS, 0); + gpio_set_level(DISPLAY_BACKLIGHT_PIN, 0); + gpio_set_level(BSP_SPI3_HOST_PCLK, 0); + gpio_set_level(BSP_SPI3_HOST_DATA0, 0); + gpio_set_level(BSP_SPI3_HOST_DATA1, 0); + gpio_set_level(BSP_SPI3_HOST_DATA2, 0); + gpio_set_level(BSP_SPI3_HOST_DATA3, 0); + + } + + esp_err_t IoExpanderSetLevel(uint16_t pin_mask, uint8_t level) { + return esp_io_expander_set_level(io_exp_handle, pin_mask, level); + } + + uint8_t IoExpanderGetLevel(uint16_t pin_mask) { + uint32_t pin_val = 0; + esp_io_expander_get_level(io_exp_handle, DRV_IO_EXP_INPUT_MASK, &pin_val); + pin_mask &= DRV_IO_EXP_INPUT_MASK; + return (uint8_t)((pin_val & pin_mask) ? 1 : 0); + } + + void InitializeExpander() { + esp_err_t ret = ESP_OK; + esp_io_expander_new_i2c_tca95xx_16bit(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_001, &io_exp_handle); + + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_INPUT_MASK, IO_EXPANDER_INPUT); + ret |= esp_io_expander_set_dir(io_exp_handle, DRV_IO_EXP_OUTPUT_MASK, IO_EXPANDER_OUTPUT); + ret |= esp_io_expander_set_level(io_exp_handle, DRV_IO_EXP_OUTPUT_MASK, 0); + ret |= esp_io_expander_set_level(io_exp_handle, BSP_PWR_SYSTEM, 1); + vTaskDelay(100 / portTICK_PERIOD_MS); + ret |= esp_io_expander_set_level(io_exp_handle, BSP_PWR_START_UP, 1); + vTaskDelay(50 / portTICK_PERIOD_MS); + + uint32_t pin_val = 0; + ret |= esp_io_expander_get_level(io_exp_handle, DRV_IO_EXP_INPUT_MASK, &pin_val); + ESP_LOGI(TAG, "IO expander initialized: %x", DRV_IO_EXP_OUTPUT_MASK | (uint16_t)pin_val); + + assert(ret == ESP_OK); + } + + void OnKnobRotate(bool clockwise) { + auto codec = GetAudioCodec(); + int current_volume = codec->output_volume(); + int new_volume = current_volume + (clockwise ? -5 : 5); + + // 确保音量在有效范围内 + if (new_volume > 100) { + new_volume = 100; + ESP_LOGW(TAG, "Volume reached maximum limit: %d", new_volume); + } else if (new_volume < 0) { + new_volume = 0; + ESP_LOGW(TAG, "Volume reached minimum limit: %d", new_volume); + } + + codec->SetOutputVolume(new_volume); + ESP_LOGI(TAG, "Volume changed from %d to %d", current_volume, new_volume); + + // 显示通知前检查实际变化 + if (new_volume != codec->output_volume()) { + ESP_LOGE(TAG, "Failed to set volume! Expected:%d Actual:%d", + new_volume, codec->output_volume()); + } + GetDisplay()->ShowNotification(std::string(Lang::Strings::VOLUME) + ": "+std::to_string(codec->output_volume())); + power_save_timer_->WakeUp(); + } + + void InitializeKnob() { + knob_ = std::make_unique(BSP_KNOB_A_PIN, BSP_KNOB_B_PIN); + knob_->OnRotate([this](bool clockwise) { + ESP_LOGD(TAG, "Knob rotation detected. Clockwise:%s", clockwise ? "true" : "false"); + OnKnobRotate(clockwise); + }); + ESP_LOGI(TAG, "Knob initialized with pins A:%d B:%d", BSP_KNOB_A_PIN, BSP_KNOB_B_PIN); + } + + void InitializeButton() { + // 设置静态实例指针 + instance_ = this; + + // watcher 是通过长按滚轮进行开机的, 需要等待滚轮释放, 否则用户开机松手时可能会误触成单击 + ESP_LOGI(TAG, "waiting for knob button release"); + while(IoExpanderGetLevel(BSP_KNOB_BTN) == 0) { + vTaskDelay(pdMS_TO_TICKS(50)); + } + + button_config_t btn_config = { + .long_press_time = 2000, + .short_press_time = 0 + }; + btn_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t)); + btn_driver_->enable_power_save = false; + btn_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t { + return !instance_->IoExpanderGetLevel(BSP_KNOB_BTN); + }; + + ESP_ERROR_CHECK(iot_button_create(&btn_config, btn_driver_, &btns)); + + iot_button_register_cb(btns, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + self->ResetWifiConfiguration(); + } + self->power_save_timer_->WakeUp(); + app.ToggleChatState(); + }, this); + + iot_button_register_cb(btns, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + bool is_charging = (self->IoExpanderGetLevel(BSP_PWR_VBUS_IN_DET) == 0); + self->long_press_cnt_ = 0; + if (is_charging) { + ESP_LOGI(TAG, "charging"); + } else { + self->IoExpanderSetLevel(BSP_PWR_LCD, 0); + self->IoExpanderSetLevel(BSP_PWR_SYSTEM, 0); + } + }, this); + + iot_button_register_cb(btns, BUTTON_LONG_PRESS_HOLD, nullptr, [](void* button_handle, void* usr_data) { + auto self = static_cast(usr_data); + self->long_press_cnt_++; // 每隔20ms加一 + // 长按10s 恢复出厂设置: 2+0.02*400 = 10 + if (self->long_press_cnt_ > 400) { + ESP_LOGI(TAG, "Factory reset"); + nvs_flash_erase(); + esp_restart(); + } + }, this); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SSCMA SPI bus"); + spi_bus_config_t spi_cfg = {0}; + + spi_cfg.mosi_io_num = BSP_SPI2_HOST_MOSI; + spi_cfg.miso_io_num = BSP_SPI2_HOST_MISO; + spi_cfg.sclk_io_num = BSP_SPI2_HOST_SCLK; + spi_cfg.quadwp_io_num = -1; + spi_cfg.quadhd_io_num = -1; + spi_cfg.isr_cpu_id = ESP_INTR_CPU_AFFINITY_1; + spi_cfg.max_transfer_sz = 4095; + + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &spi_cfg, SPI_DMA_CH_AUTO)); + + ESP_LOGI(TAG, "Initialize QSPI bus"); + + spi_bus_config_t qspi_cfg = {0}; + qspi_cfg.sclk_io_num = BSP_SPI3_HOST_PCLK; + qspi_cfg.data0_io_num = BSP_SPI3_HOST_DATA0; + qspi_cfg.data1_io_num = BSP_SPI3_HOST_DATA1; + qspi_cfg.data2_io_num = BSP_SPI3_HOST_DATA2; + qspi_cfg.data3_io_num = BSP_SPI3_HOST_DATA3; + qspi_cfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * DRV_LCD_BITS_PER_PIXEL / 8 / CONFIG_BSP_LCD_SPI_DMA_SIZE_DIV; + + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &qspi_cfg, SPI_DMA_CH_AUTO)); + } + + void Initializespd2010Display() { + ESP_LOGI(TAG, "Install panel IO"); + const esp_lcd_panel_io_spi_config_t io_config = { + .cs_gpio_num = BSP_LCD_SPI_CS, + .dc_gpio_num = -1, + .spi_mode = 3, + .pclk_hz = DRV_LCD_PIXEL_CLK_HZ, + .trans_queue_depth = 2, + .lcd_cmd_bits = DRV_LCD_CMD_BITS, + .lcd_param_bits = DRV_LCD_PARAM_BITS, + .flags = { + .quad_mode = true, + }, + }; + spd2010_vendor_config_t vendor_config = { + .flags = { + .use_qspi_interface = 1, + }, + }; + esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)BSP_LCD_SPI_NUM, &io_config, &panel_io_); + + ESP_LOGD(TAG, "Install LCD driver"); + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = BSP_LCD_GPIO_RST, // Shared with Touch reset + .rgb_ele_order = DRV_LCD_RGB_ELEMENT_ORDER, + .bits_per_pixel = DRV_LCD_BITS_PER_PIXEL, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_spd2010(panel_io_, &panel_config, &panel_); + + esp_lcd_panel_reset(panel_); + esp_lcd_panel_init(panel_); + esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel_, true); + + display_ = new CustomLcdDisplay(panel_io_, panel_, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + // 使每次刷新的起始列数索引是4的倍数且列数总数是4的倍数,以满足SPD2010的要求 + lv_display_add_event_cb(lv_display_get_default(), [](lv_event_t *e) { + lv_area_t *area = (lv_area_t *)lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + // round the start of area down to the nearest 4N number + area->x1 = (x1 >> 2) << 2; + // round the end of area up to the nearest 4M+3 number + area->x2 = ((x2 >> 2) << 2) + 3; + }, LV_EVENT_INVALIDATE_AREA, NULL); + + } + + uint16_t BatterygetVoltage(void) { + static bool initialized = false; + static adc_oneshot_unit_handle_t adc_handle; + static adc_cali_handle_t cali_handle = NULL; + if (!initialized) { + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + }; + adc_oneshot_new_unit(&init_config, &adc_handle); + + adc_oneshot_chan_cfg_t ch_config = { + .atten = BSP_BAT_ADC_ATTEN, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + adc_oneshot_config_channel(adc_handle, BSP_BAT_ADC_CHAN, &ch_config); + + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = ADC_UNIT_1, + .chan = BSP_BAT_ADC_CHAN, + .atten = BSP_BAT_ADC_ATTEN, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + if (adc_cali_create_scheme_curve_fitting(&cali_config, &cali_handle) == ESP_OK) { + initialized = true; + } + } + if (initialized) { + int raw_value = 0; + int voltage = 0; // mV + adc_oneshot_read(adc_handle, BSP_BAT_ADC_CHAN, &raw_value); + adc_cali_raw_to_voltage(cali_handle, raw_value, &voltage); + voltage = voltage * 82 / 20; + // ESP_LOGI(TAG, "voltage: %dmV", voltage); + return (uint16_t)voltage; + } + return 0; + } + + uint8_t BatterygetPercent(bool print = false) { + int voltage = 0; + for (uint8_t i = 0; i < 10; i++) { + voltage += BatterygetVoltage(); + } + voltage /= 10; + int percent = (-1 * voltage * voltage + 9016 * voltage - 19189000) / 10000; + percent = (percent > 100) ? 100 : (percent < 0) ? 0 : percent; + if (print) { + printf("voltage: %dmV, percentage: %d%%\r\n", voltage, percent); + } + return (uint8_t)percent; + } + + void InitializeCmd() { + esp_console_repl_t *repl = NULL; + esp_console_repl_config_t repl_config = ESP_CONSOLE_REPL_CONFIG_DEFAULT(); + repl_config.max_cmdline_length = 1024; + repl_config.prompt = "SenseCAP>"; + + const esp_console_cmd_t cmd1 = { + .command = "reboot", + .help = "reboot the device", + .hint = nullptr, + .func = [](int argc, char** argv) -> int { + esp_restart(); + return 0; + }, + .argtable = nullptr + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd1)); + + const esp_console_cmd_t cmd2 = { + .command = "shutdown", + .help = "shutdown the device", + .hint = nullptr, + .func = NULL, + .argtable = NULL, + .func_w_context = [](void *context,int argc, char** argv) -> int { + auto self = static_cast(context); + self->GetBacklight()->SetBrightness(0); + self->IoExpanderSetLevel(BSP_PWR_SYSTEM, 0); + return 0; + }, + .context =this + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd2)); + + const esp_console_cmd_t cmd3 = { + .command = "battery", + .help = "get battery percent", + .hint = NULL, + .func = NULL, + .argtable = NULL, + .func_w_context = [](void *context,int argc, char** argv) -> int { + auto self = static_cast(context); + self->BatterygetPercent(true); + return 0; + }, + .context =this + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd3)); + + const esp_console_cmd_t cmd4 = { + .command = "factory_reset", + .help = "factory reset and reboot the device", + .hint = NULL, + .func = NULL, + .argtable = NULL, + .func_w_context = [](void *context,int argc, char** argv) -> int { + nvs_flash_erase(); + esp_restart(); + return 0; + }, + .context =this + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd4)); + + const esp_console_cmd_t cmd5 = { + .command = "read_mac", + .help = "Read mac address", + .hint = NULL, + .func = NULL, + .argtable = NULL, + .func_w_context = [](void *context,int argc, char** argv) -> int { + uint8_t mac[6]; + esp_read_mac(mac, ESP_MAC_WIFI_STA); + printf("wifi_sta_mac: " MACSTR "\n", MAC2STR(mac)); + esp_read_mac(mac, ESP_MAC_WIFI_SOFTAP); + printf("wifi_softap_mac: " MACSTR "\n", MAC2STR(mac)); + esp_read_mac(mac, ESP_MAC_BT); + printf("bt_mac: " MACSTR "\n", MAC2STR(mac)); + return 0; + }, + .context =this + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd5)); + + const esp_console_cmd_t cmd6 = { + .command = "version", + .help = "Read version info", + .hint = NULL, + .func = NULL, + .argtable = NULL, + .func_w_context = [](void *context,int argc, char** argv) -> int { + auto self = static_cast(context); + auto app_desc = esp_app_get_description(); + const char* region = "UNKNOWN"; + #if defined(CONFIG_LANGUAGE_ZH_CN) + region = "CN"; + #elif defined(CONFIG_LANGUAGE_EN_US) + region = "US"; + #elif defined(CONFIG_LANGUAGE_JA_JP) + region = "JP"; + #elif defined(CONFIG_LANGUAGE_ES_ES) + region = "ES"; + #elif defined(CONFIG_LANGUAGE_DE_DE) + region = "DE"; + #elif defined(CONFIG_LANGUAGE_FR_FR) + region = "FR"; + #elif defined(CONFIG_LANGUAGE_IT_IT) + region = "IT"; + #elif defined(CONFIG_LANGUAGE_PT_PT) + region = "PT"; + #elif defined(CONFIG_LANGUAGE_RU_RU) + region = "RU"; + #elif defined(CONFIG_LANGUAGE_KO_KR) + region = "KR"; + #endif + printf("{\"type\":0,\"name\":\"VER?\",\"code\":0,\"data\":{\"software\":\"%s\",\"hardware\":\"watcher xiaozhi agent\",\"camera\":%d,\"region\":\"%s\"}}\n", + app_desc->version, + self->GetCamera() == nullptr ? 0 : 1, + region); + return 0; + }, + .context =this + }; + ESP_ERROR_CHECK(esp_console_cmd_register(&cmd6)); + + esp_console_dev_uart_config_t hw_config = ESP_CONSOLE_DEV_UART_CONFIG_DEFAULT(); + ESP_ERROR_CHECK(esp_console_new_repl_uart(&hw_config, &repl_config, &repl)); + ESP_ERROR_CHECK(esp_console_start_repl(repl)); + } + + void InitializeCamera() { + + ESP_LOGI(TAG, "Initialize Camera"); + + // !!!NOTE: SD Card use same SPI bus as sscma client, so we need to disable SD card CS pin first + const gpio_config_t io_config = { + .pin_bit_mask = (1ULL << BSP_SD_SPI_CS), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_ENABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + esp_err_t ret = gpio_config(&io_config); + if (ret != ESP_OK) + return; + + gpio_set_level(BSP_SD_SPI_CS, 1); + + camera_ = new SscmaCamera(io_exp_handle); + } + +public: + SensecapWatcher() { + ESP_LOGI(TAG, "Initialize Sensecap Watcher"); + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeSpi(); + InitializeExpander(); + InitializeCmd(); //工厂生产测试使用 + InitializeButton(); + InitializeKnob(); + Initializespd2010Display(); + GetBacklight()->RestoreBrightness(); // 对于不带摄像头的版本,InitializeCamera需要3s, 所以先恢复背光亮度 + InitializeCamera(); + } + + virtual AudioCodec* GetAudioCodec() override { + static SensecapAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7243E_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + // 根据 https://github.com/Seeed-Studio/OSHW-SenseCAP-Watcher/blob/main/Hardware/SenseCAP_Watcher_v1.0_SCH.pdf + // RGB LED型号为 ws2813 mini, 连接在GPIO 40,供电电压 3.3v, 没有连接 BIN 双信号线 + // 可以直接兼容SingleLED采用的ws2812 + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = (IoExpanderGetLevel(BSP_PWR_VBUS_IN_DET) == 0); + discharging = !charging; + level = (int)BatterygetPercent(false); + + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + if (level <= 1 && discharging) { + ESP_LOGI(TAG, "Battery level is low, shutting down"); + IoExpanderSetLevel(BSP_PWR_SYSTEM, 0); + } + return true; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(SensecapWatcher); + +// 定义静态成员变量 +SensecapWatcher* SensecapWatcher::instance_ = nullptr; diff --git a/main/boards/sensecap-watcher/sscma_camera.cc b/main/boards/sensecap-watcher/sscma_camera.cc new file mode 100644 index 0000000..918275e --- /dev/null +++ b/main/boards/sensecap-watcher/sscma_camera.cc @@ -0,0 +1,743 @@ +#include "sscma_camera.h" +#include "mcp_server.h" +#include "lvgl_display.h" +#include "lvgl_image.h" +#include "board.h" +#include "system_info.h" +#include "config.h" +#include "settings.h" + +#include +#include +#include +#include "application.h" +#include "sscma_client_commands.h" + +#define TAG "SscmaCamera" + +#define IMG_JPEG_BUF_SIZE 48 * 1024 + +static bool __himax_keepalive_check(sscma_client_handle_t client) +{ + esp_err_t ret = ESP_OK; + sscma_client_reply_t reply = {0}; + int retry = 3; + while(retry--) { + ret = sscma_client_request(client, CMD_PREFIX CMD_AT_ID CMD_QUERY CMD_SUFFIX, &reply, true, pdMS_TO_TICKS(2000)); + if (reply.payload != NULL) { + sscma_client_reply_clear(&reply); + } + if( ret != ESP_OK ) { + ESP_LOGE(TAG, "Himax keepalive check failed: %d", ret); + vTaskDelay(pdMS_TO_TICKS(100)); + } else { + return true; + } + } + return false; +} + +SscmaCamera::SscmaCamera(esp_io_expander_handle_t io_exp_handle) { + sscma_client_io_spi_config_t spi_io_config = {0}; + spi_io_config.sync_gpio_num = BSP_SSCMA_CLIENT_SPI_SYNC; + spi_io_config.cs_gpio_num = BSP_SSCMA_CLIENT_SPI_CS; + spi_io_config.pclk_hz = BSP_SSCMA_CLIENT_SPI_CLK; + spi_io_config.spi_mode = 0; + spi_io_config.wait_delay = 10; //两个transfer之间至少延时4ms,但当前 FREERTOS_HZ=100, 延时精度只能达到10ms, + spi_io_config.user_ctx = NULL; + spi_io_config.io_expander = io_exp_handle; + spi_io_config.flags.sync_use_expander = BSP_SSCMA_CLIENT_RST_USE_EXPANDER; + + sscma_client_new_io_spi_bus((sscma_client_spi_bus_handle_t)BSP_SSCMA_CLIENT_SPI_NUM, &spi_io_config, &sscma_client_io_handle_); + + sscma_client_config_t sscma_client_config = SSCMA_CLIENT_CONFIG_DEFAULT(); + sscma_client_config.event_queue_size = CONFIG_SSCMA_EVENT_QUEUE_SIZE; + sscma_client_config.tx_buffer_size = CONFIG_SSCMA_TX_BUFFER_SIZE; + sscma_client_config.rx_buffer_size = CONFIG_SSCMA_RX_BUFFER_SIZE; + sscma_client_config.process_task_stack = CONFIG_SSCMA_PROCESS_TASK_STACK_SIZE; + sscma_client_config.process_task_affinity = CONFIG_SSCMA_PROCESS_TASK_AFFINITY; + sscma_client_config.process_task_priority = CONFIG_SSCMA_PROCESS_TASK_PRIORITY; + sscma_client_config.monitor_task_stack = CONFIG_SSCMA_MONITOR_TASK_STACK_SIZE; + sscma_client_config.monitor_task_affinity = CONFIG_SSCMA_MONITOR_TASK_AFFINITY; + sscma_client_config.monitor_task_priority = CONFIG_SSCMA_MONITOR_TASK_PRIORITY; + sscma_client_config.reset_gpio_num = BSP_SSCMA_CLIENT_RST; + sscma_client_config.io_expander = io_exp_handle; + sscma_client_config.flags.reset_use_expander = BSP_SSCMA_CLIENT_RST_USE_EXPANDER; + + sscma_client_new(sscma_client_io_handle_, &sscma_client_config, &sscma_client_handle_); + + sscma_data_queue_ = xQueueCreate(1, sizeof(SscmaData)); + + sscma_client_callback_t callback = {0}; + + detection_state = SscmaCamera::IDLE; + state_start_time = 0; + need_start_cooldown = false; + callback.on_event = [](sscma_client_handle_t client, const sscma_client_reply_t *reply, void *user_ctx) { + SscmaCamera* self = static_cast(user_ctx); + if (!self) return; + + char *img = NULL; + int img_size = 0; + int box_count = 0; + sscma_client_box_t *boxes = NULL; + int class_count = 0; + sscma_client_class_t *classes = NULL; + int point_count = 0; + sscma_client_point_t *points = NULL; + int model_type = 0; + int obj_cnt = 0; + + int width = 0, height = 0; + cJSON *data = cJSON_GetObjectItem(reply->payload, "data"); + if (data != NULL && cJSON_IsObject(data)) { + cJSON *resolution = cJSON_GetObjectItem(data, "resolution"); + if (data != NULL && cJSON_IsArray(resolution) && cJSON_GetArraySize(resolution) == 2) { + width = cJSON_GetArrayItem(resolution, 0)->valueint; + height = cJSON_GetArrayItem(resolution, 1)->valueint; + } + } + + switch ((width+height)) { + case (416+416): + { + bool is_object_detected = false; + bool is_need_wake = false; + + // 定期更新检测配置参数,避免频繁NVS访问 + int64_t cur_tm = esp_timer_get_time(); + + // 尝试获取检测框数据(目标检测模型) + if (sscma_utils_fetch_boxes_from_reply(reply, &boxes, &box_count) == ESP_OK && box_count > 0) { + for (int i = 0; i < box_count; i++) { + ESP_LOGI(TAG, "[box %d]: x=%d, y=%d, w=%d, h=%d, score=%d, target=%d", i, \ + boxes[i].x, boxes[i].y, boxes[i].w, boxes[i].h, boxes[i].score, boxes[i].target); + if (boxes[i].target == self->detect_target && boxes[i].score > self->detect_threshold) { + is_object_detected = true; + model_type = 0; + obj_cnt++; + break; + } + } + free(boxes); + } else if (sscma_utils_fetch_classes_from_reply(reply, &classes, &class_count) == ESP_OK && class_count > 0) { + // 尝试获取分类数据(分类模型) + for (int i = 0; i < class_count; i++) { + ESP_LOGI(TAG, "[class %d]: target=%d, score=%d", i, + classes[i].target, classes[i].score); + if (classes[i].target == self->detect_target && classes[i].score > self->detect_threshold) { + is_object_detected = true; + model_type = 1; + obj_cnt++; + } + } + free(classes); + } else if (sscma_utils_fetch_points_from_reply(reply, &points, &point_count) == ESP_OK && point_count > 0) { + // 尝试获取关键点数据(姿态估计模型) + for (int i = 0; i < point_count; i++) { + ESP_LOGI(TAG, "[point %d]: x=%d, y=%d, z=%d, score=%d, target=%d", i, + points[i].x, points[i].y, points[i].z, points[i].score, points[i].target); + if (points[i].target == self->detect_target && points[i].score > self->detect_threshold) { + is_object_detected = true; + model_type = 2; + obj_cnt++; + } + } + free(points); + } + + // 如果需要开始冷却期,现在开始计时 + if (self->need_start_cooldown) { // 回调暂停,标志保持,等待回调恢复后开始计时 + self->state_start_time = cur_tm; + self->need_start_cooldown = false; + ESP_LOGI(TAG, "Starting cooldown timer"); + } + + // 状态机驱动的检测逻辑 - 只在人员出现时触发 + switch (self->detection_state) { + case SscmaCamera::IDLE: + if (is_object_detected) { + // 人员出现,开始验证(这是从无到有的转换) + self->detection_state = SscmaCamera::VALIDATING; + self->state_start_time = cur_tm; // 记录物体出现时间 + self->last_detected_time = cur_tm; // 初始化最后检测时间 + ESP_LOGI(TAG, "object appeared, starting validation"); + } + break; + + case SscmaCamera::VALIDATING: + if (is_object_detected) { + // 更新最后检测到的时间 + self->last_detected_time = cur_tm; + // 检查是否验证足够时间 + if ((cur_tm - self->state_start_time) >= (self->detect_duration_sec * 1000000)) { + is_need_wake = true; + } + } else { + // 验证期间人员离开,检查去抖动时间 + if (self->last_detected_time > 0 && + (cur_tm - self->last_detected_time) >= self->detect_debounce_sec * 1000000LL) { + // 去抖动时间已过,确认人员已离开,回到空闲 + self->detection_state = SscmaCamera::IDLE; + self->last_detected_time = 0; + ESP_LOGI(TAG, "object left during validation (debounced), back to idle"); + } + } + break; + + case SscmaCamera::COOLDOWN: + // 冷却期,需要满足两个条件:1)object离开 2)过了15秒 + if (!is_object_detected && + (cur_tm - self->state_start_time) >= (self->detect_invoke_interval_sec * 1000000LL)) { + // object离开且冷却时间到,回到空闲状态 + self->detection_state = SscmaCamera::IDLE; + ESP_LOGI(TAG, "Cooldown complete and object left, back to idle - ready for next appearance"); + } + // 其他情况继续保持冷却状态 + break; + } + + + if( is_need_wake ) { + ESP_LOGI(TAG, "Validation complete, triggering conversation (type=%d, res=%dx%d)", + self->detect_target, width, height); + + // 触发对话 + std::string wake_word; + if ( model_type == 0 ) { + std::string cached_target_name = "object"; + if( self->model != NULL && self->model->classes[self->detect_target] != NULL ) { + cached_target_name = self->model->classes[self->detect_target]; + } + wake_word = "" + std::to_string(obj_cnt) + " " + cached_target_name + " detected "; + } else if ( model_type == 1 ) { + std::string cached_target_name = "object"; + if( self->model != NULL && self->model->classes[self->detect_target] != NULL ) { + cached_target_name = self->model->classes[self->detect_target]; + } + wake_word = "" + std::to_string(obj_cnt) + " " + cached_target_name + " detected "; + } else if ( model_type == 2 ) { + std::string cached_target_name = "object"; + if( self->model != NULL && self->model->classes[self->detect_target] != NULL ) { + cached_target_name = self->model->classes[self->detect_target]; + } + wake_word = "" + std::to_string(obj_cnt) + " " + cached_target_name + " detected "; + } + printf("wake_word:%s\n", wake_word.c_str()); + Application::GetInstance().WakeWordInvoke(wake_word); + + // 进入冷却状态,标记需要开始冷却期;如下变量将在会话结束后被使用,等待回调恢复后开始计时 + self->detection_state = SscmaCamera::COOLDOWN; + self->need_start_cooldown = true; + } + } + break; + case (640+480): + + if (sscma_utils_fetch_image_from_reply(reply, &img, &img_size) == ESP_OK) + { + ESP_LOGI(TAG, "image_size: %d\n", img_size); + // 将数据通过队列发送出去 + SscmaData data; + data.img = (uint8_t*)img; + data.len = img_size; + + // 清空队列,保证只保存最新的数据 + SscmaData dummy; + while (xQueueReceive(self->sscma_data_queue_, &dummy, 0) == pdPASS) { + if (dummy.img) { + heap_caps_free(dummy.img); + } + } + xQueueSend(self->sscma_data_queue_, &data, 0); + // 注意:img 的释放由接收方负责 + } + break; + default: + ESP_LOGI(TAG, "unknown resolution"); + break; + } + }; + callback.on_connect = [](sscma_client_handle_t client, const sscma_client_reply_t *reply, void *user_ctx) { + ESP_LOGI(TAG, "SSCMA client connected"); + SscmaCamera* self = static_cast(user_ctx); + if (self) { + self->sscma_restarted_ = true; + } + }; + + callback.on_log = [](sscma_client_handle_t client, const sscma_client_reply_t *reply, void *user_ctx) { + ESP_LOGI(TAG, "log: %s\n", reply->data); + }; + + sscma_client_register_callback(sscma_client_handle_, &callback, this); + + sscma_client_init(sscma_client_handle_); + + ESP_LOGI(TAG, "SSCMA client initialized"); + // 设置分辨率 + // 3 = 640x480 + if (sscma_client_set_sensor(sscma_client_handle_, 1, 3, true)) { + ESP_LOGE(TAG, "Failed to set sensor"); + sscma_client_del(sscma_client_handle_); + sscma_client_handle_ = NULL; + return; + } + + // 获取设备信息 + sscma_client_info_t *info; + if (sscma_client_get_info(sscma_client_handle_, &info, true) == ESP_OK) { + ESP_LOGI(TAG, "Device Info - ID: %s, Name: %s", + info->id ? info->id : "NULL", + info->name ? info->name : "NULL"); + } + // 初始化JPEG数据的内存 + jpeg_data_.len = 0; + jpeg_data_.buf = (uint8_t*)heap_caps_malloc(IMG_JPEG_BUF_SIZE, MALLOC_CAP_SPIRAM);; + if ( jpeg_data_.buf == nullptr ) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG buffer"); + return; + } + + //初始化JPEG解码 + jpeg_error_t err; + jpeg_dec_config_t config = { .output_type = JPEG_PIXEL_FORMAT_RGB565_LE, .rotate = JPEG_ROTATE_0D }; + err = jpeg_dec_open(&config, &jpeg_dec_); + if ( err != JPEG_ERR_OK ) { + ESP_LOGE(TAG, "Failed to open JPEG decoder"); + return; + } + jpeg_io_ = (jpeg_dec_io_t*)heap_caps_malloc(sizeof(jpeg_dec_io_t), MALLOC_CAP_SPIRAM); + if (!jpeg_io_) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG IO"); + jpeg_dec_close(jpeg_dec_); + return; + } + memset(jpeg_io_, 0, sizeof(jpeg_dec_io_t)); + + jpeg_out_ = (jpeg_dec_header_info_t*)heap_caps_aligned_alloc(16, sizeof(jpeg_dec_header_info_t), MALLOC_CAP_SPIRAM); + if (!jpeg_out_) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG output header"); + heap_caps_free(jpeg_io_); + jpeg_dec_close(jpeg_dec_); + return; + } + memset(jpeg_out_, 0, sizeof(jpeg_dec_header_info_t)); + + // 初始化预览图片的内存 + memset(&preview_image_, 0, sizeof(preview_image_)); + preview_image_.header.magic = LV_IMAGE_HEADER_MAGIC; + preview_image_.header.cf = LV_COLOR_FORMAT_RGB565; + preview_image_.header.flags = LV_IMAGE_FLAGS_ALLOCATED | LV_IMAGE_FLAGS_MODIFIABLE; + preview_image_.header.w = 640; + preview_image_.header.h = 480; + + preview_image_.header.stride = preview_image_.header.w * 2; + preview_image_.data_size = preview_image_.header.w * preview_image_.header.h * 2; + preview_image_.data =(uint8_t*)jpeg_calloc_align(preview_image_.data_size, 16); + if (preview_image_.data == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for preview image"); + return; + } + + sscma_client_set_model(sscma_client_handle_, 4); + model_class_cnt = 0; + if (sscma_client_get_model(sscma_client_handle_, &model, true) == ESP_OK) { + printf("ID: %d\n", model->id ? model->id : -1); + printf("UUID: %s\n", model->uuid ? model->uuid : "N/A"); + printf("Name: %s\n", model->name ? model->name : "N/A"); + printf("Version: %s\n", model->ver ? model->ver : "N/A"); + printf("URL: %s\n", model->url ? model->url : "N/A"); + printf("Checksum: %s\n", model->checksum ? model->checksum : "N/A"); + printf("Classes:\n"); + if (model->classes[0] != NULL) + { + for (int i = 0; model->classes[i] != NULL; i++) + { + printf(" - %s\n", model->classes[i]); + model_class_cnt++; + } + } else { + printf(" N/A\n"); + } + } else { + printf("get model failed\n"); + } + + ESP_LOGI(TAG, "initialize mcp tools"); + InitializeMcpTools(); + + xTaskCreate([](void* arg) { + auto this_ = (SscmaCamera*)arg; + bool is_inference = false; + int64_t last_keepalive_time = esp_timer_get_time(); + while (true) + { + if (this_->sscma_restarted_) { + ESP_LOGI(TAG, "SSCMA restarted detected"); + this_->sscma_restarted_ = false; + is_inference = false; + } + + if (esp_timer_get_time() - last_keepalive_time > 10 * 1000000) { + last_keepalive_time = esp_timer_get_time(); + if (!__himax_keepalive_check(this_->sscma_client_handle_)) { + ESP_LOGE(TAG, "restart himax"); + sscma_client_reset(this_->sscma_client_handle_); + vTaskDelay(pdMS_TO_TICKS(100)); + } + } + + if (this_->inference_en && Application::GetInstance().GetDeviceState() == kDeviceStateIdle ) { + if (!is_inference) { + ESP_LOGI(TAG, "Start inference (enable=1)"); + sscma_client_break(this_->sscma_client_handle_); + sscma_client_set_model(this_->sscma_client_handle_, 4); + sscma_client_set_sensor(this_->sscma_client_handle_, 1, 1, true); // 设置分辨率 416X416 + sscma_client_invoke(this_->sscma_client_handle_, -1, false, true); + is_inference = true; + } + } else if (is_inference && (!this_->inference_en || Application::GetInstance().GetDeviceState() != kDeviceStateIdle)) { + ESP_LOGI(TAG, "Stop inference (enable=%d state=%d)", this_->inference_en, Application::GetInstance().GetDeviceState()); + is_inference = false; + sscma_client_break(this_->sscma_client_handle_); + } + vTaskDelay(pdMS_TO_TICKS(200)); + } + }, "sscma_camera", 4096, this, 1, nullptr); + +} + +SscmaCamera::~SscmaCamera() { + if (preview_image_.data) { + heap_caps_free((void*)preview_image_.data); + preview_image_.data = nullptr; + } + if (sscma_client_handle_) { + sscma_client_del(sscma_client_handle_); + } + if (sscma_data_queue_) { + vQueueDelete(sscma_data_queue_); + } + if (jpeg_data_.buf) { + heap_caps_free(jpeg_data_.buf); + jpeg_data_.buf = nullptr; + } + if (jpeg_dec_) { + jpeg_dec_close(jpeg_dec_); + jpeg_dec_ = nullptr; + } + if (jpeg_io_) { + heap_caps_free(jpeg_io_); + jpeg_io_ = nullptr; + } + if (jpeg_out_) { + heap_caps_free(jpeg_out_); + jpeg_out_ = nullptr; + } +} + +void SscmaCamera::InitializeMcpTools() { + + Settings settings("model", false); + detect_threshold = settings.GetInt("threshold", 75); + detect_invoke_interval_sec = settings.GetInt("interval", 8); + detect_duration_sec = settings.GetInt("duration", 2); + detect_target = settings.GetInt("target", 0); + inference_en = settings.GetInt("enable", 0); + + auto& mcp_server = McpServer::GetInstance(); + // 获取模型参数配置 + mcp_server.AddTool("self.model.param_get", + "获取当前视觉模型检测的参数配置信息。\n" + "返回结果包含:\n" + " `threshold`: 检测置信度阈值 (0-100),低于此值的检测结果将被忽略;\n" + " `interval`: 触发对话后的冷却时间(秒),防止频繁打断;\n" + " `duration`: 持续检测确认时间(秒);\n" + " `target`: 当前关注的检测目标索引。", + PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + Settings settings("model", false); + int threshold = settings.GetInt("threshold", 75); + int interval = settings.GetInt("interval", 8); + int duration = settings.GetInt("duration", 2); + int target_type = settings.GetInt("target", 0); + + std::string result = "{\"threshold\":" + std::to_string(threshold) + + ",\"interval\":" + std::to_string(interval) + + ",\"duration\":" + std::to_string(duration) + + ",\"target_type\":" + std::to_string(target_type) + "}"; + return result; + }); + + + // 设置模型参数配置 + mcp_server.AddTool("self.model.param_set", + "配置视觉模型检测参数。当用户希望调整检测灵敏度、频率或特定目标时使用。\n" + "参数(均为可选,未提供的参数将保持当前设置不变):\n" + " `threshold`: 置信度阈值 (0-100)。提高此值可减少误报,但可能漏检;\n" + " `interval`: 冷却时间(秒)。设置对话结束后多久内不再触发检测;\n" + " `duration`: 持续检测时间(秒)。\n" + " `target`: 设置检测目标的索引 ID。", + PropertyList({ + Property("threshold", kPropertyTypeInteger, -1, -1, 100), + Property("interval", kPropertyTypeInteger, -1, -1, 60), + Property("duration", kPropertyTypeInteger, -1, -1, 60), + Property("target", kPropertyTypeInteger, -1, -1, this->model_class_cnt > 0 ? this->model_class_cnt - 1 : 255) + }), + [this](const PropertyList& properties) -> ReturnValue { + Settings settings("model", true); + try { + const Property& threshold_prop = properties["threshold"]; + int threshold = threshold_prop.value(); + if (threshold != -1) { + settings.SetInt("threshold", threshold); + this->detect_threshold = threshold; + ESP_LOGI(TAG, "Set detection threshold to %d", threshold); + } + } catch (const std::runtime_error&) { + // threshold parameter not provided, skip + } + + try { + const Property& interval_prop = properties["interval"]; + int interval = interval_prop.value(); + if (interval != -1) { + settings.SetInt("interval", interval); + this->detect_invoke_interval_sec = interval; + ESP_LOGI(TAG, "Set detection interval to %d", interval); + } + } catch (const std::runtime_error&) { + // interval parameter not provided, skip + } + + try { + const Property& duration_prop = properties["duration"]; + int duration = duration_prop.value(); + if (duration != -1) { + settings.SetInt("duration", duration); + this->detect_duration_sec = duration; + } + } catch (const std::runtime_error&) { + // duration parameter not provided, skip + } + + try { + const Property& target_prop = properties["target"]; + int target = target_prop.value(); + if (target != -1) { + settings.SetInt("target", target); + this->detect_target = target; + ESP_LOGI(TAG, "Set detection target to %d", target); + } + } catch (const std::runtime_error&) { + // target_type parameter not provided, skip + } + + return "{\"status\": \"success\", \"message\": \"Detection configuration updated\"}"; + }); + + // 推理开关获取 + mcp_server.AddTool("self.model.enable", + "控制视觉推理(摄像头检测)功能的开启与关闭,或查询当前状态。\n" + "当用户指令涉及'开启/关闭推理'、'开始/停止检测'时使用。\n" + "参数:\n" + " `enable`: (可选) 整数。1=开启推理,0=关闭推理。若省略则返回当前开关状态。", + PropertyList({ + Property("enable", kPropertyTypeInteger, inference_en, 0, 1) + }), + [this](const PropertyList& properties) -> ReturnValue { + Settings settings("model", true); + try { + const Property& enable_prop = properties["enable"]; + int en = enable_prop.value(); + settings.SetInt("enable", en); + this->inference_en = en; + ESP_LOGI(TAG, "Set inference enable to %d", en); + } catch (const std::runtime_error&) { + // enable not provided -> treat as query + } + // 返回当前配置 + int cur_en = settings.GetInt("enable", this->inference_en); + return std::string("{\"enable\":") + std::to_string(cur_en) + "}"; + }); +} + +void SscmaCamera::SetExplainUrl(const std::string& url, const std::string& token) { + explain_url_ = url; + explain_token_ = token; +} + +bool SscmaCamera::Capture() { + + SscmaData data; + int ret = 0; + + if (sscma_client_handle_ == nullptr) { + ESP_LOGE(TAG, "SSCMA client handle is not initialized"); + return false; + } + + if (sscma_client_set_sensor(sscma_client_handle_, 1, 3, true)) { + ESP_LOGE(TAG, "Failed to set sensor"); + return false; + } + ESP_LOGI(TAG, "Capturing image..."); + // himax 可能有缓存数据, 只获取最新的照片即可. + if (sscma_client_sample(sscma_client_handle_, 1) ) { + ESP_LOGE(TAG, "Failed to capture image from SSCMA client"); + return false; + } + vTaskDelay(pdMS_TO_TICKS(500)); // 等待SSCMA客户端处理数据 + if (xQueueReceive(sscma_data_queue_, &data, pdMS_TO_TICKS(1000)) != pdPASS) { + ESP_LOGE(TAG, "Failed to receive JPEG data from SSCMA client"); + return false; + } + + if (jpeg_data_.buf == nullptr) { + heap_caps_free(data.img); + return false; + } + + ret = mbedtls_base64_decode(jpeg_data_.buf, IMG_JPEG_BUF_SIZE, &jpeg_data_.len, data.img, data.len); + if (ret != 0 || jpeg_data_.len == 0) { + ESP_LOGE(TAG, "Failed to decode base64 image data, ret: %d, output_len: %zu", ret, jpeg_data_.len); + heap_caps_free(data.img); + return false; + } + heap_caps_free(data.img); + + //DECODE JPEG + if (!jpeg_dec_ || !jpeg_io_ || !jpeg_out_ || !preview_image_.data) { + return true; + } + jpeg_io_->inbuf = jpeg_data_.buf; + jpeg_io_->inbuf_len = jpeg_data_.len; + ret = jpeg_dec_parse_header(jpeg_dec_, jpeg_io_, jpeg_out_); + if (ret < 0) { + ESP_LOGE(TAG, "Failed to parse JPEG header, ret: %d", ret); + return true; + } + jpeg_io_->outbuf = (unsigned char*)preview_image_.data; + int inbuf_consumed = jpeg_io_->inbuf_len - jpeg_io_->inbuf_remain; + jpeg_io_->inbuf = jpeg_data_.buf + inbuf_consumed; + jpeg_io_->inbuf_len = jpeg_io_->inbuf_remain; + + ret = jpeg_dec_process(jpeg_dec_, jpeg_io_); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to decode JPEG image, ret: %d", ret); + return true; + } + + // 显示预览图片 + auto display = dynamic_cast(Board::GetInstance().GetDisplay()); + if (display != nullptr) { + uint16_t w = preview_image_.header.w; + uint16_t h = preview_image_.header.h; + size_t image_size = w * h * 2; + size_t stride = preview_image_.header.w * 2; + + uint8_t* data = (uint8_t*)heap_caps_malloc(image_size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (data == nullptr) { + ESP_LOGE(TAG, "Failed to allocate memory for display image"); + return true; + } + memcpy(data, preview_image_.data, image_size); + + auto image = std::make_unique(data, image_size, w, h, stride, LV_COLOR_FORMAT_RGB565); + display->SetPreviewImage(std::move(image)); + } + return true; +} +bool SscmaCamera::SetHMirror(bool enabled) { + return false; +} + +bool SscmaCamera::SetVFlip(bool enabled) { + return false; +} + +/** + * @brief 将摄像头捕获的图像发送到远程服务器进行AI分析和解释 + * + * 该函数将当前摄像头缓冲区中的图像编码为JPEG格式,并通过HTTP POST请求 + * 以multipart/form-data的形式发送到指定的解释服务器。服务器将根据提供的 + * 问题对图像进行AI分析并返回结果。 + * + * @param question 要向AI提出的关于图像的问题,将作为表单字段发送 + * @return std::string 服务器返回的JSON格式响应字符串 + * 成功时包含AI分析结果,失败时包含错误信息 + * 格式示例:{"success": true, "result": "分析结果"} + * {"success": false, "message": "错误信息"} + * + * @note 调用此函数前必须先调用SetExplainUrl()设置服务器URL + * @note 函数会等待之前的编码线程完成后再开始新的处理 + * @warning 如果摄像头缓冲区为空或网络连接失败,将返回错误信息 + */ +std::string SscmaCamera::Explain(const std::string& question) { + if (explain_url_.empty()) { + return "{\"success\": false, \"message\": \"Image explain URL or token is not set\"}"; + } + + auto network = Board::GetInstance().GetNetwork(); + auto http = network->CreateHttp(3); + // 构造multipart/form-data请求体 + std::string boundary = "----ESP32_CAMERA_BOUNDARY"; + + // 构造question字段 + std::string question_field; + question_field += "--" + boundary + "\r\n"; + question_field += "Content-Disposition: form-data; name=\"question\"\r\n"; + question_field += "\r\n"; + question_field += question + "\r\n"; + + // 构造文件字段头部 + std::string file_header; + file_header += "--" + boundary + "\r\n"; + file_header += "Content-Disposition: form-data; name=\"file\"; filename=\"camera.jpg\"\r\n"; + file_header += "Content-Type: image/jpeg\r\n"; + file_header += "\r\n"; + + // 构造尾部 + std::string multipart_footer; + multipart_footer += "\r\n--" + boundary + "--\r\n"; + + // 配置HTTP客户端,使用分块传输编码 + http->SetHeader("Device-Id", SystemInfo::GetMacAddress().c_str()); + http->SetHeader("Client-Id", Board::GetInstance().GetUuid().c_str()); + if (!explain_token_.empty()) { + http->SetHeader("Authorization", "Bearer " + explain_token_); + } + http->SetHeader("Content-Type", "multipart/form-data; boundary=" + boundary); + http->SetHeader("Transfer-Encoding", "chunked"); + if (!http->Open("POST", explain_url_)) { + ESP_LOGE(TAG, "Failed to connect to explain URL"); + return "{\"success\": false, \"message\": \"Failed to connect to explain URL\"}"; + } + + // 第一块:question字段 + http->Write(question_field.c_str(), question_field.size()); + + // 第二块:文件字段头部 + http->Write(file_header.c_str(), file_header.size()); + + // 第三块:JPEG数据 + http->Write((const char*)jpeg_data_.buf, jpeg_data_.len); + + // 第四块:multipart尾部 + http->Write(multipart_footer.c_str(), multipart_footer.size()); + + // 结束块 + http->Write("", 0); + + if (http->GetStatusCode() != 200) { + ESP_LOGE(TAG, "Failed to upload photo, status code: %d", http->GetStatusCode()); + return "{\"success\": false, \"message\": \"Failed to upload photo\"}"; + } + + std::string result = http->ReadAll(); + http->Close(); + + ESP_LOGI(TAG, "Explain image size=%d, question=%s\n%s", jpeg_data_.len, question.c_str(), result.c_str()); + return result; +} diff --git a/main/boards/sensecap-watcher/sscma_camera.h b/main/boards/sensecap-watcher/sscma_camera.h new file mode 100644 index 0000000..40d6777 --- /dev/null +++ b/main/boards/sensecap-watcher/sscma_camera.h @@ -0,0 +1,75 @@ +#ifndef SSCMA_CAMERA_H +#define SSCMA_CAMERA_H + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "sscma_client.h" +#include "camera.h" + +struct SscmaData { + uint8_t* img; + size_t len; +}; +struct JpegData { + uint8_t* buf; + size_t len; +}; + +class SscmaCamera : public Camera { +private: + lv_img_dsc_t preview_image_; + std::string explain_url_; + std::string explain_token_; + sscma_client_io_handle_t sscma_client_io_handle_; + sscma_client_handle_t sscma_client_handle_; + QueueHandle_t sscma_data_queue_; + JpegData jpeg_data_; + jpeg_dec_handle_t jpeg_dec_; + jpeg_dec_io_t *jpeg_io_; + jpeg_dec_header_info_t *jpeg_out_; + // 检测状态机 + enum DetectionState { + IDLE, // 空闲状态 + VALIDATING, // 验证中(连续检测3秒) + COOLDOWN // 冷却期(等待重新检测) + }; + + DetectionState detection_state = IDLE; + int64_t state_start_time = 0; + bool need_start_cooldown = false; // 是否需要开始冷却期 + int64_t last_detected_time = 0; // 验证期间最后一次检测到物体的时间 + + int detect_target = 0; + int detect_threshold = 75; + int detect_duration_sec = 2; // 检测持续时间2秒,确认人员持续存在 + int detect_invoke_interval_sec = 8; // 默认15秒冷却期,避免频繁开始会话 + int detect_debounce_sec = 1; // 验证期间人员离开的去抖动时间1秒 + int inference_en = 0; // 推理使能开关(0: 关闭, 1: 开启) + bool sscma_restarted_ = false; + + sscma_client_model_t *model; + int model_class_cnt = 0; +public: + SscmaCamera(esp_io_expander_handle_t io_exp_handle); + ~SscmaCamera(); + void InitializeMcpTools(); + + virtual void SetExplainUrl(const std::string& url, const std::string& token); + virtual bool Capture(); + // 翻转控制函数 + virtual bool SetHMirror(bool enabled) override; + virtual bool SetVFlip(bool enabled) override; + virtual std::string Explain(const std::string& question); + +}; + +#endif // ESP32_CAMERA_H diff --git a/main/boards/sp-esp32-s3-1.28-box/README.md b/main/boards/sp-esp32-s3-1.28-box/README.md new file mode 100644 index 0000000..84b854b --- /dev/null +++ b/main/boards/sp-esp32-s3-1.28-box/README.md @@ -0,0 +1,31 @@ +【产品简介】 +】支持触摸 +】支持充电 +】独特外形设计 +产品链接1:https://spotpear.cn/shop/ESP32-S3-N16R8-AI-DeepSeek-XiaoZhi-XiaGe-Qwen-DouBao-1.28-inch-LCD.html +产品链接2:https://spotpear.cn/shop/ESP32-S3-N16R8-AI-DeepSeek-XiaoZhi-XiaGe-Qwen-DouBao-1.28-inch-Round-LCD-BOX-TouchScreen.html +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> Spotpear ESP32-S3-1.28-BOX +``` + +**编译:** + +```bash +idf.py build +``` diff --git a/main/boards/sp-esp32-s3-1.28-box/config.h b/main/boards/sp-esp32-s3-1.28-box/config.h new file mode 100644 index 0000000..cde7dcb --- /dev/null +++ b/main/boards/sp-esp32-s3-1.28-box/config.h @@ -0,0 +1,56 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// Movecall Moji configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 //MCLK +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 //LRCK +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 //SCLK +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 //DOUT +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 //DIN + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_42 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_4 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_2 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_5 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_47 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_38 + +#define TP_PIN_NUM_TP_SDA (GPIO_NUM_11) +#define TP_PIN_NUM_TP_SCL (GPIO_NUM_7) +#define TP_PIN_NUM_TP_RST (GPIO_NUM_6) +#define TP_PIN_NUM_TP_INT (GPIO_NUM_12) + +#define DISPLAY_SPI_SCLK_HZ (40 * 1000 * 1000) + +// 电量检测相关引脚定义 +#define BATTERY_ADC_PIN GPIO_NUM_1 // 电池电压检测ADC引脚 +#define BATTERY_CHARGING_PIN GPIO_NUM_41 // 充电状态检测引脚 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/sp-esp32-s3-1.28-box/config.json b/main/boards/sp-esp32-s3-1.28-box/config.json new file mode 100644 index 0000000..db34c1c --- /dev/null +++ b/main/boards/sp-esp32-s3-1.28-box/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "sp-esp32-s3-1.28-box", + "sdkconfig_append": [] + } + ] +} diff --git a/main/boards/sp-esp32-s3-1.28-box/power_manager.h b/main/boards/sp-esp32-s3-1.28-box/power_manager.h new file mode 100644 index 0000000..36e8ca9 --- /dev/null +++ b/main/boards/sp-esp32-s3-1.28-box/power_manager.h @@ -0,0 +1,189 @@ +#pragma once +#include +#include + +#include +#include +#include +#include +#include + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + adc_channel_t adc_channel_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, adc_channel_, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 - 根据实际硬件调整这些值 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1980, 0}, + {2081, 20}, + {2163, 40}, + {2250, 60}, + {2340, 80}, + {2480, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t charging_pin, adc_channel_t adc_channel) + : charging_pin_(charging_pin), adc_channel_(adc_channel) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 100000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, adc_channel_, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; \ No newline at end of file diff --git a/main/boards/sp-esp32-s3-1.28-box/sp-esp32-s3-1.28-box.cc b/main/boards/sp-esp32-s3-1.28-box/sp-esp32-s3-1.28-box.cc new file mode 100644 index 0000000..77364b9 --- /dev/null +++ b/main/boards/sp-esp32-s3-1.28-box/sp-esp32-s3-1.28-box.cc @@ -0,0 +1,482 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include +#include +#include +#include + +#include +#include +#include +#include "system_reset.h" +#include "driver/gpio.h" +#include "driver/spi_master.h" +#include +#include "i2c_device.h" +#include +#include +#include "power_save_timer.h" +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "power_manager.h" + +#define TAG "Spotpear_ESP32_S3_1_28_BOX" + +LV_FONT_DECLARE(font_puhui_16_4); +LV_FONT_DECLARE(font_awesome_16_4); + + +class Cst816d : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + Cst816d(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA3); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + last_chip_id_ = chip_id; + read_buffer_ = new uint8_t[6]; + } + + ~Cst816d() { + if (read_buffer_) { + delete[] read_buffer_; + read_buffer_ = nullptr; + } + } + + void UpdateTouchPoint() { + if (!read_buffer_) return; + ReadRegs(0x02, read_buffer_, 6); + if (read_buffer_[0] == 0xFF) { + read_buffer_[0] = 0x00; + } + tp_.num = read_buffer_[0] & 0x01; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t& GetTouchPoint() const { + return tp_; + } + + static bool Probe(i2c_master_bus_handle_t i2c_bus, uint8_t addr, uint8_t& chip_id) { + if (!i2c_bus) return false; + i2c_master_dev_handle_t dev = nullptr; + i2c_device_config_t cfg = { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = addr, + .scl_speed_hz = 400 * 1000, + .scl_wait_us = 0, + .flags = { + .disable_ack_check = 0, + }, + }; + esp_err_t ret = i2c_master_bus_add_device(i2c_bus, &cfg, &dev); + if (ret != ESP_OK || dev == nullptr) { + return false; + } + uint8_t reg = 0xA3; + uint8_t id = 0; + ret = i2c_master_transmit_receive(dev, ®, 1, &id, 1, 100); + i2c_master_bus_rm_device(dev); + if (ret == ESP_OK) { + chip_id = id; + return true; + } + return false; + } + +private: + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; + uint8_t last_chip_id_ = 0; +}; + + +class CustomLcdDisplay : public SpiLcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + + DisplayLockGuard lock(this); + // 由于屏幕是圆的,所以状态栏需要增加左右内边距 + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES * 0.33, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES * 0.33, 0); + } +}; + + +class Spotpear_ESP32_S3_1_28_BOX : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_ = nullptr; + i2c_master_bus_handle_t i2c_bus_ = nullptr; + Button boot_button_; + Display* display_ = nullptr; + esp_timer_handle_t touchpad_timer_ = nullptr; + Cst816d* cst816d_ = nullptr; + PowerSaveTimer* power_save_timer_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + PowerManager* power_manager_ = nullptr; + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_3); + rtc_gpio_set_direction(GPIO_NUM_3, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_3, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 290); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + // 关闭ES8311音频编解码器 + auto codec = GetAudioCodec(); + if (codec) { + codec->EnableInput(false); + codec->EnableOutput(false); + } + rtc_gpio_set_level(GPIO_NUM_3, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_3); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(BATTERY_CHARGING_PIN, ADC_CHANNEL_0); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + // .glitch_ignore_cnt = 7, + // .intr_priority = 0, + // .trans_queue_depth = 0, + // .flags = { + // .enable_internal_pullup = 1, + // }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeCodecI2c_Touch() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = TP_PIN_NUM_TP_SDA, + .scl_io_num = TP_PIN_NUM_TP_SCL, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + esp_err_t ret = i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "i2c_new_master_bus failed: %s", esp_err_to_name(ret)); + i2c_bus_ = nullptr; + } + } + + + static void touchpad_timer_callback(void* arg) { + auto* board = static_cast(arg); + if (!board || !board->cst816d_) return; + static bool was_touched = false; + static int64_t touch_start_time = 0; + const int64_t TOUCH_THRESHOLD_MS = 500; // 触摸时长阈值,超过500ms视为长按 + + board->cst816d_->UpdateTouchPoint(); + auto touch_point = board->cst816d_->GetTouchPoint(); + + // 检测触摸开始 + if (touch_point.num > 0 && !was_touched) { + was_touched = true; + touch_start_time = esp_timer_get_time() / 1000; // 转换为毫秒 + } + // 检测触摸释放 + else if (touch_point.num == 0 && was_touched) { + was_touched = false; + int64_t touch_duration = (esp_timer_get_time() / 1000) - touch_start_time; + + // 只有短触才触发 + if (touch_duration < TOUCH_THRESHOLD_MS) { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + board->ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + } + } + + void InitializeCst816DTouchPad() { + ESP_LOGI(TAG, "Init Cst816D"); + + // RST/INT 管脚初始化 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << TP_PIN_NUM_TP_RST); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + gpio_config_t int_conf = {}; + int_conf.intr_type = GPIO_INTR_DISABLE; + int_conf.mode = GPIO_MODE_INPUT; + int_conf.pin_bit_mask = (1ULL << TP_PIN_NUM_TP_INT); + int_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + int_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&int_conf); + + // 触摸芯片复位序列 + gpio_set_level(TP_PIN_NUM_TP_RST, 0); + vTaskDelay(pdMS_TO_TICKS(5)); + gpio_set_level(TP_PIN_NUM_TP_RST, 1); + vTaskDelay(pdMS_TO_TICKS(50)); + + // 探测是否存在触摸芯片 + uint8_t chip_id = 0; + if (!i2c_bus_) { + ESP_LOGW(TAG, "Touch I2C bus not initialized, skip touch"); + return; + } + bool touch_available = Cst816d::Probe(i2c_bus_, 0x15, chip_id); + if (!touch_available) { + ESP_LOGW(TAG, "CST816D not found, running in non-touch mode"); + // 释放触摸I2C,避免无设备时反复报错 + i2c_del_master_bus(i2c_bus_); + i2c_bus_ = nullptr; + return; + } + + cst816d_ = new Cst816d(i2c_bus_, 0x15); + + // 创建定时器,10ms 间隔 + esp_timer_create_args_t timer_args = { + .callback = touchpad_timer_callback, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "touchpad_timer", + .skip_unhandled_events = true, + }; + + if (esp_timer_create(&timer_args, &touchpad_timer_) == ESP_OK) { + esp_timer_start_periodic(touchpad_timer_, 10 * 1000); // 10ms = 10000us + } + } + + // SPI初始化 + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize SPI bus"); + spi_bus_config_t buscfg = GC9A01_PANEL_BUS_SPI_CONFIG(DISPLAY_SPI_SCLK_PIN, DISPLAY_SPI_MOSI_PIN, + DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + // GC9A01初始化 + void InitializeGc9a01Display() { + ESP_LOGI(TAG, "Init GC9A01 display"); + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_lcd_panel_io_spi_config_t io_config = GC9A01_PANEL_IO_SPI_CONFIG(DISPLAY_SPI_CS_PIN, DISPLAY_SPI_DC_PIN, 0, NULL); + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &io_handle)); + + ESP_LOGI(TAG, "Install GC9A01 panel driver"); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; // Set to -1 if not use + panel_config.rgb_endian = LCD_RGB_ENDIAN_BGR; //LCD_RGB_ENDIAN_RGB; + panel_config.bits_per_pixel = 16; + + ESP_ERROR_CHECK(esp_lcd_new_panel_gc9a01(io_handle, &panel_config, &panel_handle)); + panel_ = panel_handle; + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_handle, true)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_handle, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_handle, true)); + + uint8_t data_0x62[] = { 0x18, 0x0D, 0x71, 0xED, 0x70, 0x70, 0x18, 0x0F, 0x71, 0xEF, 0x70, 0x70 }; + esp_lcd_panel_io_tx_param(io_handle, 0x62, data_0x62, sizeof(data_0x62)); + + uint8_t data_0x63[] = { 0x18, 0x11, 0x71, 0xF1, 0x70, 0x70, 0x18, 0x13, 0x71, 0xF3, 0x70, 0x70 }; + esp_lcd_panel_io_tx_param(io_handle, 0x63, data_0x63, sizeof(data_0x63)); + + uint8_t data_0x36[] = { 0x48}; + esp_lcd_panel_io_tx_param(io_handle, 0x36, data_0x36, sizeof(data_0x36)); + + // uint8_t data_0x74[] = { 0x10, 0x85, 0x80, 0x00, 0x00, 0x4E, 0x00}; + // esp_lcd_panel_io_tx_param(io_handle, 0x74, data_0x74, sizeof(data_0x74)); + + uint8_t data_0xC3[] = { 0x1F}; + esp_lcd_panel_io_tx_param(io_handle, 0xC3, data_0xC3, sizeof(data_0xC3)); + + uint8_t data_0xC4[] = { 0x1F}; + esp_lcd_panel_io_tx_param(io_handle, 0xC4, data_0xC4, sizeof(data_0xC4)); + + display_ = new CustomLcdDisplay(io_handle, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + Spotpear_ESP32_S3_1_28_BOX() : boot_button_(BOOT_BUTTON_GPIO) { + // 先初始化触摸的I2C并探测/初始化触摸(若无触摸则跳过) + InitializeCodecI2c_Touch(); + InitializeCst816DTouchPad(); + + // 初始化音频I2C + InitializeCodecI2c(); + + // 显示相关先建立起来 + InitializeSpi(); + InitializeGc9a01Display(); + InitializeButtons(); + if (GetBacklight()) { + GetBacklight()->RestoreBrightness(); + } + + // 显示和背光可用后再初始化省电逻辑,避免空指针 + InitializePowerSaveTimer(); + InitializePowerManager(); + } + + ~Spotpear_ESP32_S3_1_28_BOX() { + if (touchpad_timer_) { + esp_timer_stop(touchpad_timer_); + esp_timer_delete(touchpad_timer_); + touchpad_timer_ = nullptr; + } + if (cst816d_) { + delete cst816d_; + cst816d_ = nullptr; + } + if (power_save_timer_) { + delete power_save_timer_; + power_save_timer_ = nullptr; + } + if (power_manager_) { + delete power_manager_; + power_manager_ = nullptr; + } + if (display_) { + delete display_; + display_ = nullptr; + } + if (i2c_bus_) { + i2c_del_master_bus(i2c_bus_); + i2c_bus_ = nullptr; + } + if (codec_i2c_bus_) { + i2c_del_master_bus(codec_i2c_bus_); + codec_i2c_bus_ = nullptr; + } + } + + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + Cst816d* GetTouchpad() { + return cst816d_; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + if (!power_manager_) { + level = 0; + charging = false; + discharging = true; + return false; + } + + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(Spotpear_ESP32_S3_1_28_BOX); diff --git a/main/boards/sp-esp32-s3-1.54-muma/README.md b/main/boards/sp-esp32-s3-1.54-muma/README.md new file mode 100644 index 0000000..94a00bb --- /dev/null +++ b/main/boards/sp-esp32-s3-1.54-muma/README.md @@ -0,0 +1,34 @@ +【产品简介】 +[] ESP32 S3小木马开发板1.54寸LCD小智muma虾哥AI DeepSeek人工智能语音聊天机器人N16R8 +【功能】 +[] 可爱小木马,支持天气时钟, SD视频播放, AI智能对话所有固件源码开源,适合小孩编程学习,可开发更多功能。 +AI小智支持语音唤醒。触摸版本额外支持触摸唤醒和打断 +显示屏:1.54寸ST7789 240x240分辨率 +产品链接: +https://spotpear.cn/shop/ESP32-S3-AI-1.54-inch-LCD-Display-TouchScreen-N16R8-muma-DeepSeek/sp-esp32-s3-1.54-muma-W-Bat.html + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> Spotpear ESP32-S3-LCD-1.54-MUMA +``` + +**编译:** + +```bash +idf.py build +``` diff --git a/main/boards/sp-esp32-s3-1.54-muma/config.h b/main/boards/sp-esp32-s3-1.54-muma/config.h new file mode 100644 index 0000000..a13ce75 --- /dev/null +++ b/main/boards/sp-esp32-s3-1.54-muma/config.h @@ -0,0 +1,58 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// Movecall Moji configuration + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 //MCLK +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 //LRCK +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 //SCLK +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 //DOUT +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 //DIN + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_42 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#define DISPLAY_SPI_SCLK_PIN GPIO_NUM_4 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_2 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_5 +#define DISPLAY_SPI_DC_PIN GPIO_NUM_47 +#define DISPLAY_SPI_RESET_PIN GPIO_NUM_38 + + +#define TP_PIN_NUM_TP_SDA (GPIO_NUM_11) +#define TP_PIN_NUM_TP_SCL (GPIO_NUM_7) +#define TP_PIN_NUM_TP_RST (GPIO_NUM_6) +#define TP_PIN_NUM_TP_INT (GPIO_NUM_12) + +#define POWER_CHARGE_LED_PIN GPIO_NUM_3 +#define POWER_CHARGE_DETECT_PIN GPIO_NUM_41 +#define POWER_ADC_UNIT ADC_UNIT_1 +#define POWER_ADC_CHANNEL ADC_CHANNEL_0 + +#define DISPLAY_SPI_SCLK_HZ (40 * 1000 * 1000) + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/sp-esp32-s3-1.54-muma/config.json b/main/boards/sp-esp32-s3-1.54-muma/config.json new file mode 100644 index 0000000..2bc4d1b --- /dev/null +++ b/main/boards/sp-esp32-s3-1.54-muma/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "sp-esp32-s3-1.54-muma", + "sdkconfig_append": [] + } + ] +} diff --git a/main/boards/sp-esp32-s3-1.54-muma/power_manager.h b/main/boards/sp-esp32-s3-1.54-muma/power_manager.h new file mode 100644 index 0000000..2df53a1 --- /dev/null +++ b/main/boards/sp-esp32-s3-1.54-muma/power_manager.h @@ -0,0 +1,186 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_41; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_0, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1980, 0}, + {2081, 20}, + {2163, 40}, + {2250, 60}, + {2340, 80}, + {2480, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 100000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_0, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/sp-esp32-s3-1.54-muma/sp-esp32-s3-1.54-muma.cc b/main/boards/sp-esp32-s3-1.54-muma/sp-esp32-s3-1.54-muma.cc new file mode 100644 index 0000000..436cc34 --- /dev/null +++ b/main/boards/sp-esp32-s3-1.54-muma/sp-esp32-s3-1.54-muma.cc @@ -0,0 +1,325 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include +#include +#include +#include "system_reset.h" + +#include +#include + +#include "driver/gpio.h" +#include "driver/spi_master.h" +#include +#include +#include +#include "i2c_device.h" +#include +#include "power_manager.h" +#include "power_save_timer.h" +#include +#include + +#define TAG "Spotpear_esp32_s3_lcd_1_54" + +class Cst816d : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + Cst816d(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA3); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Cst816d() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t& GetTouchPoint() { + return tp_; + } + +private: + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class Spotpear_esp32_s3_lcd_1_54 : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Display* display_; + esp_timer_handle_t touchpad_timer_; + Cst816d* cst816d_; + esp_io_expander_handle_t io_expander_ = NULL; + esp_lcd_panel_handle_t panel_ = nullptr; + + PowerManager* power_manager_; + PowerSaveTimer* power_save_timer_; + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_41); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_3); + rtc_gpio_set_direction(GPIO_NUM_3, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_3, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_3, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_3); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeCodecI2c_Touch() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = TP_PIN_NUM_TP_SDA, + .scl_io_num = TP_PIN_NUM_TP_SCL, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static void touchpad_timer_callback(void* arg) { + auto& board = (Spotpear_esp32_s3_lcd_1_54&)Board::GetInstance(); + auto touchpad = board.GetTouchpad(); + static bool was_touched = false; + static int64_t touch_start_time = 0; + const int64_t TOUCH_THRESHOLD_MS = 500; // 触摸时长阈值,超过500ms视为长按 + + touchpad->UpdateTouchPoint(); + auto touch_point = touchpad->GetTouchPoint(); + // 检测触摸开始 + if (touch_point.num > 0 && !was_touched) { + was_touched = true; + touch_start_time = esp_timer_get_time() / 1000; // 转换为毫秒 + } + // 检测触摸释放 + else if (touch_point.num == 0 && was_touched) { + was_touched = false; + int64_t touch_duration = (esp_timer_get_time() / 1000) - touch_start_time; + + // 只有短触才触发 + if (touch_duration < TOUCH_THRESHOLD_MS) { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + board.ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + } + } + + void InitializeCst816DTouchPad() { + ESP_LOGI(TAG, "Init Cst816D"); + cst816d_ = new Cst816d(i2c_bus_, 0x15); + + // 创建定时器,10ms 间隔 + esp_timer_create_args_t timer_args = { + .callback = touchpad_timer_callback, + .arg = NULL, + .dispatch_method = ESP_TIMER_TASK, + .name = "touchpad_timer", + .skip_unhandled_events = true, + }; + + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &touchpad_timer_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(touchpad_timer_, 10 * 1000)); // 10ms = 10000us + } + + void EnableLcdCs() { + if(io_expander_ != NULL) { + esp_io_expander_set_level(io_expander_, DISPLAY_SPI_CS_PIN, 0);// 置低 LCD CS + } + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SPI_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_SPI_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 60 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_RESET_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + EnableLcdCs(); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + + // uint8_t data_0xBB[] = { 0x3F }; + // esp_lcd_panel_io_tx_param(panel_io, 0xBB, data_0xBB, sizeof(data_0xBB)); + + uint8_t data_0xBB[] = { 0x38 }; + esp_lcd_panel_io_tx_param(panel_io, 0xBB, data_0xBB, sizeof(data_0xBB)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + +public: + + Spotpear_esp32_s3_lcd_1_54() :boot_button_(BOOT_BUTTON_GPIO){ + gpio_set_direction(TP_PIN_NUM_TP_INT, GPIO_MODE_INPUT); + int level = gpio_get_level(TP_PIN_NUM_TP_INT); + if (level == 1) { + InitializeCodecI2c_Touch(); + InitializeCst816DTouchPad(); + } + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeSpi(); + InitializePowerManager(); + InitializeSt7789Display(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + + } + + virtual Led* GetLed() override { + static SingleLed led_strip(BUILTIN_LED_GPIO); + return &led_strip; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst816d* GetTouchpad() { + return cst816d_; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(Spotpear_esp32_s3_lcd_1_54); diff --git a/main/boards/surfer-c3-1.14tft/README.md b/main/boards/surfer-c3-1.14tft/README.md new file mode 100644 index 0000000..9a6d211 --- /dev/null +++ b/main/boards/surfer-c3-1.14tft/README.md @@ -0,0 +1,5 @@ +## Surfer-ESP32-C3 开发板 + +1、参考立创·实战派C3-ESP32C3开发板,修改了TFT屏幕背光引脚,增加ADC电池电量检测功能; +2、该开发板 flash 大小为 16MB,编译时注意选择默认的分区表。 + diff --git a/main/boards/surfer-c3-1.14tft/config.h b/main/boards/surfer-c3-1.14tft/config.h new file mode 100644 index 0000000..7970330 --- /dev/null +++ b/main/boards/surfer-c3-1.14tft/config.h @@ -0,0 +1,45 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_11 + +// #define AUDIO_CODEC_USE_PCA9557 +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_0 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +// #define AUDIO_CODEC_ES7210_ADDR 0x82 + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_9 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SPI_SCK_PIN GPIO_NUM_3 +#define DISPLAY_SPI_MOSI_PIN GPIO_NUM_5 +#define DISPLAY_DC_PIN GPIO_NUM_6 +#define DISPLAY_SPI_CS_PIN GPIO_NUM_4 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 135 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY true + +#define DISPLAY_OFFSET_X 40 +#define DISPLAY_OFFSET_Y 53 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/surfer-c3-1.14tft/config.json b/main/boards/surfer-c3-1.14tft/config.json new file mode 100644 index 0000000..a8f30ad --- /dev/null +++ b/main/boards/surfer-c3-1.14tft/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "surfer-c3-1.14tft", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_USE_ESP_WAKE_WORD=y", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/surfer-c3-1.14tft/power_manager.h b/main/boards/surfer-c3-1.14tft/power_manager.h new file mode 100644 index 0000000..22643b8 --- /dev/null +++ b/main/boards/surfer-c3-1.14tft/power_manager.h @@ -0,0 +1,201 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_2, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {3060, 0}, + {3200, 20}, + {3340, 40}, + {3480, 60}, + {3620, 80}, + {3760, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + + + if (charging_pin_ != GPIO_NUM_NC) { + // 不初始化 ADC,不检测 + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + } + + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_2_5, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_2, &chan_config)); + ESP_LOGI("PowerManager ADC INIT------------------", + "ADC atten: ADC_ATTEN_DB_2_5, bitwidth: ADC_BITWIDTH_DEFAULT ADC chan: ADC_CHANNEL_2"); + + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + if (charging_pin_ == GPIO_NUM_NC) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + if (charging_pin_ == GPIO_NUM_NC) { + return false; + } + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/surfer-c3-1.14tft/surfer-c3-1.14tft.cc b/main/boards/surfer-c3-1.14tft/surfer-c3-1.14tft.cc new file mode 100644 index 0000000..cad05c6 --- /dev/null +++ b/main/boards/surfer-c3-1.14tft/surfer-c3-1.14tft.cc @@ -0,0 +1,210 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "power_save_timer.h" +#include "power_manager.h" +// #include + +#define TAG "SURFERC3114TFT" + +class SurferC3114TFT : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_NC); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + + } + + void InitializePowerSaveTimer() { + //定时器,调整设备为modem-sleep模式和屏幕亮度 + power_save_timer_ = new PowerSaveTimer(-1, 60, -1); + power_save_timer_->OnEnterSleepMode([this]() { + ESP_LOGI(TAG, "Enabling modem-sleep mode"); + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + esp_wifi_set_ps(WIFI_PS_MIN_MODEM); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + esp_wifi_set_ps(WIFI_PS_NONE); // 关闭Wi-Fi省电,恢复正常 + // esp_lcd_panel_disp_on_off(panel_, true); // 重新打开显示 + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down display"); + GetBacklight()->SetBrightness(1); + // esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + // power_save_timer_->SetEnabled(false); // 禁用定时器,防止重复 + + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SPI_SCK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeSt7789Display() { + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io_)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + + esp_lcd_panel_reset(panel_); + + esp_lcd_panel_init(panel_); + esp_lcd_panel_invert_color(panel_, true); + esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io_, panel_, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + SurferC3114TFT() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + InitializeButtons(); + + GetBacklight()->RestoreBrightness(); + + // 把 ESP32C3 的 VDD SPI 引脚作为普通 GPIO 口使用 + esp_efuse_write_field_bit(ESP_EFUSE_VDD_SPI_AS_GPIO); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + codec_i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } + +}; + +DECLARE_BOARD(SurferC3114TFT); diff --git a/main/boards/taiji-pi-s3/README.md b/main/boards/taiji-pi-s3/README.md new file mode 100644 index 0000000..c3e7b2f --- /dev/null +++ b/main/boards/taiji-pi-s3/README.md @@ -0,0 +1,45 @@ +# 由于原来的麦克风型号停产,2025年7月之后的太极派(JC3636W518)更换了麦克风,并且更换了屏幕玻璃,所以在产品标签上批次号大于2528的用户请选择I2S Type PDM, + +# 新增双声道配置 + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> 太极小派esp32s3 + +Xiaozhi Assistant -> TAIJIPAI_S3_CONFIG -> taiji-pi-S3 I2S Type -> I2S Type PDM +``` + +**如果需要选择双声道:** +``` + +Xiaozhi Assistant -> TAIJIPAI_S3_CONFIG -> Enabel use 2 slot +``` + + +**修改PSRAM配置:** + +``` +component config -> ESP PSRAM -> SPI RAM config -> Try to allocate memories of WiFi and LWIP in SPIRAM firstly. If failed, allocate internal memory + +``` + +**编译:** + +```bash +idf.py build +``` diff --git a/main/boards/taiji-pi-s3/config.h b/main/boards/taiji-pi-s3/config.h new file mode 100644 index 0000000..c07d620 --- /dev/null +++ b/main/boards/taiji-pi-s3/config.h @@ -0,0 +1,66 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +// Taiji Pi S3 Board configuration + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_DEFAULT_OUTPUT_VOLUME 80 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_21 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_16 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_18 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_NC +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_17 +#define AUDIO_MUTE_PIN GPIO_NUM_48 // 低电平静音 + +#define AUDIO_MIC_WS_PIN GPIO_NUM_45 +#define AUDIO_MIC_SD_PIN GPIO_NUM_46 +#define AUDIO_MIC_SCK_PIN GPIO_NUM_42 + +#define DISPLAY_WIDTH 360 +#define DISPLAY_HEIGHT 360 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true +#define DISPLAY_SWAP_XY false + +#define QSPI_LCD_H_RES (360) +#define QSPI_LCD_V_RES (360) +#define QSPI_LCD_BIT_PER_PIXEL (16) + +#define QSPI_LCD_HOST SPI2_HOST +#define QSPI_PIN_NUM_LCD_PCLK GPIO_NUM_9 +#define QSPI_PIN_NUM_LCD_CS GPIO_NUM_10 +#define QSPI_PIN_NUM_LCD_DATA0 GPIO_NUM_11 +#define QSPI_PIN_NUM_LCD_DATA1 GPIO_NUM_12 +#define QSPI_PIN_NUM_LCD_DATA2 GPIO_NUM_13 +#define QSPI_PIN_NUM_LCD_DATA3 GPIO_NUM_14 +#define QSPI_PIN_NUM_LCD_RST GPIO_NUM_47 +#define QSPI_PIN_NUM_LCD_BL GPIO_NUM_15 + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define TP_PORT (I2C_NUM_1) +#define TP_PIN_NUM_TP_SDA (GPIO_NUM_7) +#define TP_PIN_NUM_TP_SCL (GPIO_NUM_8) +#define TP_PIN_NUM_TP_RST (GPIO_NUM_40) +#define TP_PIN_NUM_TP_INT (GPIO_NUM_41) + +#define DISPLAY_BACKLIGHT_PIN QSPI_PIN_NUM_LCD_BL +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(sclk, d0, d1, d2, d3, max_trans_sz) \ + { \ + .data0_io_num = d0, \ + .data1_io_num = d1, \ + .sclk_io_num = sclk, \ + .data2_io_num = d2, \ + .data3_io_num = d3, \ + .max_transfer_sz = max_trans_sz, \ + } + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/taiji-pi-s3/config.json b/main/boards/taiji-pi-s3/config.json new file mode 100644 index 0000000..5b81784 --- /dev/null +++ b/main/boards/taiji-pi-s3/config.json @@ -0,0 +1,19 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "taiji-pi-s3", + "sdkconfig_append": [ + "CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP=y", + "CONFIG_TAIJIPAI_I2S_TYPE_STD=y" + ] + }, + { + "name": "taiji-pi-s3-pdm", + "sdkconfig_append": [ + "CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP=y", + "CONFIG_TAIJIPAI_I2S_TYPE_PDM=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/taiji-pi-s3/taiji_pi_s3.cc b/main/boards/taiji-pi-s3/taiji_pi_s3.cc new file mode 100644 index 0000000..05876c4 --- /dev/null +++ b/main/boards/taiji-pi-s3/taiji_pi_s3.cc @@ -0,0 +1,664 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "i2c_device.h" +#include "config.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#define TAG "TaijiPiS3Board" + +static const st77916_lcd_init_cmd_t lcd_init_cmds[] = { +#ifdef CONFIG_TAIJIPAI_I2S_TYPE_STD + {0xF0, (uint8_t[]){0x08}, 1, 0}, + {0xF2, (uint8_t[]){0x08}, 1, 0}, + {0x9B, (uint8_t[]){0x51}, 1, 0}, + {0x86, (uint8_t[]){0x53}, 1, 0}, + {0xF2, (uint8_t[]){0x80}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0xF0, (uint8_t[]){0x01}, 1, 0}, + {0xF1, (uint8_t[]){0x01}, 1, 0}, + {0xB0, (uint8_t[]){0x54}, 1, 0}, + {0xB1, (uint8_t[]){0x3F}, 1, 0}, + {0xB2, (uint8_t[]){0x2A}, 1, 0}, + {0xB4, (uint8_t[]){0x46}, 1, 0}, + {0xB5, (uint8_t[]){0x34}, 1, 0}, + {0xB6, (uint8_t[]){0xD5}, 1, 0}, + {0xB7, (uint8_t[]){0x30}, 1, 0}, + {0xBA, (uint8_t[]){0x00}, 1, 0}, + {0xBB, (uint8_t[]){0x08}, 1, 0}, + {0xBC, (uint8_t[]){0x08}, 1, 0}, + {0xBD, (uint8_t[]){0x00}, 1, 0}, + {0xC0, (uint8_t[]){0x80}, 1, 0}, + {0xC1, (uint8_t[]){0x10}, 1, 0}, + {0xC2, (uint8_t[]){0x37}, 1, 0}, + {0xC3, (uint8_t[]){0x80}, 1, 0}, + {0xC4, (uint8_t[]){0x10}, 1, 0}, + {0xC5, (uint8_t[]){0x37}, 1, 0}, + {0xC6, (uint8_t[]){0xA9}, 1, 0}, + {0xC7, (uint8_t[]){0x41}, 1, 0}, + {0xC8, (uint8_t[]){0x51}, 1, 0}, + {0xC9, (uint8_t[]){0xA9}, 1, 0}, + {0xCA, (uint8_t[]){0x41}, 1, 0}, + {0xCB, (uint8_t[]){0x51}, 1, 0}, + {0xD0, (uint8_t[]){0x91}, 1, 0}, + {0xD1, (uint8_t[]){0x68}, 1, 0}, + {0xD2, (uint8_t[]){0x69}, 1, 0}, + {0xF5, (uint8_t[]){0x00, 0xA5}, 2, 0}, + {0xDD, (uint8_t[]){0x3F}, 1, 0}, + {0xDE, (uint8_t[]){0x3F}, 1, 0}, + {0xF1, (uint8_t[]){0x10}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0xF0, (uint8_t[]){0x02}, 1, 0}, + {0xE0, (uint8_t[]){0x70, 0x09, 0x12, 0x0C, 0x0B, 0x27, 0x38, 0x54, 0x4E, 0x19, 0x15, 0x15, 0x2C, 0x2F}, 14, 0}, + {0xE1, (uint8_t[]){0x70, 0x08, 0x11, 0x0C, 0x0B, 0x27, 0x38, 0x43, 0x4C, 0x18, 0x14, 0x14, 0x2B, 0x2D}, 14, 0}, + {0xF0, (uint8_t[]){0x10}, 1, 0}, + {0xF3, (uint8_t[]){0x10}, 1, 0}, + {0xE0, (uint8_t[]){0x08}, 1, 0}, + {0xE1, (uint8_t[]){0x00}, 1, 0}, + {0xE2, (uint8_t[]){0x00}, 1, 0}, + {0xE3, (uint8_t[]){0x00}, 1, 0}, + {0xE4, (uint8_t[]){0xE0}, 1, 0}, + {0xE5, (uint8_t[]){0x06}, 1, 0}, + {0xE6, (uint8_t[]){0x21}, 1, 0}, + {0xE7, (uint8_t[]){0x00}, 1, 0}, + {0xE8, (uint8_t[]){0x05}, 1, 0}, + {0xE9, (uint8_t[]){0x82}, 1, 0}, + {0xEA, (uint8_t[]){0xDF}, 1, 0}, + {0xEB, (uint8_t[]){0x89}, 1, 0}, + {0xEC, (uint8_t[]){0x20}, 1, 0}, + {0xED, (uint8_t[]){0x14}, 1, 0}, + {0xEE, (uint8_t[]){0xFF}, 1, 0}, + {0xEF, (uint8_t[]){0x00}, 1, 0}, + {0xF8, (uint8_t[]){0xFF}, 1, 0}, + {0xF9, (uint8_t[]){0x00}, 1, 0}, + {0xFA, (uint8_t[]){0x00}, 1, 0}, + {0xFB, (uint8_t[]){0x30}, 1, 0}, + {0xFC, (uint8_t[]){0x00}, 1, 0}, + {0xFD, (uint8_t[]){0x00}, 1, 0}, + {0xFE, (uint8_t[]){0x00}, 1, 0}, + {0xFF, (uint8_t[]){0x00}, 1, 0}, + {0x60, (uint8_t[]){0x42}, 1, 0}, + {0x61, (uint8_t[]){0xE0}, 1, 0}, + {0x62, (uint8_t[]){0x40}, 1, 0}, + {0x63, (uint8_t[]){0x40}, 1, 0}, + {0x64, (uint8_t[]){0x02}, 1, 0}, + {0x65, (uint8_t[]){0x00}, 1, 0}, + {0x66, (uint8_t[]){0x40}, 1, 0}, + {0x67, (uint8_t[]){0x03}, 1, 0}, + {0x68, (uint8_t[]){0x00}, 1, 0}, + {0x69, (uint8_t[]){0x00}, 1, 0}, + {0x6A, (uint8_t[]){0x00}, 1, 0}, + {0x6B, (uint8_t[]){0x00}, 1, 0}, + {0x70, (uint8_t[]){0x42}, 1, 0}, + {0x71, (uint8_t[]){0xE0}, 1, 0}, + {0x72, (uint8_t[]){0x40}, 1, 0}, + {0x73, (uint8_t[]){0x40}, 1, 0}, + {0x74, (uint8_t[]){0x02}, 1, 0}, + {0x75, (uint8_t[]){0x00}, 1, 0}, + {0x76, (uint8_t[]){0x40}, 1, 0}, + {0x77, (uint8_t[]){0x03}, 1, 0}, + {0x78, (uint8_t[]){0x00}, 1, 0}, + {0x79, (uint8_t[]){0x00}, 1, 0}, + {0x7A, (uint8_t[]){0x00}, 1, 0}, + {0x7B, (uint8_t[]){0x00}, 1, 0}, + {0x80, (uint8_t[]){0x48}, 1, 0}, + {0x81, (uint8_t[]){0x00}, 1, 0}, + {0x82, (uint8_t[]){0x05}, 1, 0}, + {0x83, (uint8_t[]){0x02}, 1, 0}, + {0x84, (uint8_t[]){0xDD}, 1, 0}, + {0x85, (uint8_t[]){0x00}, 1, 0}, + {0x86, (uint8_t[]){0x00}, 1, 0}, + {0x87, (uint8_t[]){0x00}, 1, 0}, + {0x88, (uint8_t[]){0x48}, 1, 0}, + {0x89, (uint8_t[]){0x00}, 1, 0}, + {0x8A, (uint8_t[]){0x07}, 1, 0}, + {0x8B, (uint8_t[]){0x02}, 1, 0}, + {0x8C, (uint8_t[]){0xDF}, 1, 0}, + {0x8D, (uint8_t[]){0x00}, 1, 0}, + {0x8E, (uint8_t[]){0x00}, 1, 0}, + {0x8F, (uint8_t[]){0x00}, 1, 0}, + {0x90, (uint8_t[]){0x48}, 1, 0}, + {0x91, (uint8_t[]){0x00}, 1, 0}, + {0x92, (uint8_t[]){0x09}, 1, 0}, + {0x93, (uint8_t[]){0x02}, 1, 0}, + {0x94, (uint8_t[]){0xE1}, 1, 0}, + {0x95, (uint8_t[]){0x00}, 1, 0}, + {0x96, (uint8_t[]){0x00}, 1, 0}, + {0x97, (uint8_t[]){0x00}, 1, 0}, + {0x98, (uint8_t[]){0x48}, 1, 0}, + {0x99, (uint8_t[]){0x00}, 1, 0}, + {0x9A, (uint8_t[]){0x0B}, 1, 0}, + {0x9B, (uint8_t[]){0x02}, 1, 0}, + {0x9C, (uint8_t[]){0xE3}, 1, 0}, + {0x9D, (uint8_t[]){0x00}, 1, 0}, + {0x9E, (uint8_t[]){0x00}, 1, 0}, + {0x9F, (uint8_t[]){0x00}, 1, 0}, + {0xA0, (uint8_t[]){0x48}, 1, 0}, + {0xA1, (uint8_t[]){0x00}, 1, 0}, + {0xA2, (uint8_t[]){0x04}, 1, 0}, + {0xA3, (uint8_t[]){0x02}, 1, 0}, + {0xA4, (uint8_t[]){0xDC}, 1, 0}, + {0xA5, (uint8_t[]){0x00}, 1, 0}, + {0xA6, (uint8_t[]){0x00}, 1, 0}, + {0xA7, (uint8_t[]){0x00}, 1, 0}, + {0xA8, (uint8_t[]){0x48}, 1, 0}, + {0xA9, (uint8_t[]){0x00}, 1, 0}, + {0xAA, (uint8_t[]){0x06}, 1, 0}, + {0xAB, (uint8_t[]){0x02}, 1, 0}, + {0xAC, (uint8_t[]){0xDE}, 1, 0}, + {0xAD, (uint8_t[]){0x00}, 1, 0}, + {0xAE, (uint8_t[]){0x00}, 1, 0}, + {0xAF, (uint8_t[]){0x00}, 1, 0}, + {0xB0, (uint8_t[]){0x48}, 1, 0}, + {0xB1, (uint8_t[]){0x00}, 1, 0}, + {0xB2, (uint8_t[]){0x08}, 1, 0}, + {0xB3, (uint8_t[]){0x02}, 1, 0}, + {0xB4, (uint8_t[]){0xE0}, 1, 0}, + {0xB5, (uint8_t[]){0x00}, 1, 0}, + {0xB6, (uint8_t[]){0x00}, 1, 0}, + {0xB7, (uint8_t[]){0x00}, 1, 0}, + {0xB8, (uint8_t[]){0x48}, 1, 0}, + {0xB9, (uint8_t[]){0x00}, 1, 0}, + {0xBA, (uint8_t[]){0x0A}, 1, 0}, + {0xBB, (uint8_t[]){0x02}, 1, 0}, + {0xBC, (uint8_t[]){0xE2}, 1, 0}, + {0xBD, (uint8_t[]){0x00}, 1, 0}, + {0xBE, (uint8_t[]){0x00}, 1, 0}, + {0xBF, (uint8_t[]){0x00}, 1, 0}, + {0xC0, (uint8_t[]){0x12}, 1, 0}, + {0xC1, (uint8_t[]){0xAA}, 1, 0}, + {0xC2, (uint8_t[]){0x65}, 1, 0}, + {0xC3, (uint8_t[]){0x74}, 1, 0}, + {0xC4, (uint8_t[]){0x47}, 1, 0}, + {0xC5, (uint8_t[]){0x56}, 1, 0}, + {0xC6, (uint8_t[]){0x00}, 1, 0}, + {0xC7, (uint8_t[]){0x88}, 1, 0}, + {0xC8, (uint8_t[]){0x99}, 1, 0}, + {0xC9, (uint8_t[]){0x33}, 1, 0}, + {0xD0, (uint8_t[]){0x21}, 1, 0}, + {0xD1, (uint8_t[]){0xAA}, 1, 0}, + {0xD2, (uint8_t[]){0x65}, 1, 0}, + {0xD3, (uint8_t[]){0x74}, 1, 0}, + {0xD4, (uint8_t[]){0x47}, 1, 0}, + {0xD5, (uint8_t[]){0x56}, 1, 0}, + {0xD6, (uint8_t[]){0x00}, 1, 0}, + {0xD7, (uint8_t[]){0x88}, 1, 0}, + {0xD8, (uint8_t[]){0x99}, 1, 0}, + {0xD9, (uint8_t[]){0x33}, 1, 0}, + {0xF3, (uint8_t[]){0x01}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0xF0, (uint8_t[]){0x01}, 1, 0}, + {0xF1, (uint8_t[]){0x01}, 1, 0}, + {0xA0, (uint8_t[]){0x0B}, 1, 0}, + {0xA3, (uint8_t[]){0x2A}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x2B}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x2C}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x2D}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x2E}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x2F}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x30}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x31}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x32}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA3, (uint8_t[]){0x33}, 1, 0}, + {0xA5, (uint8_t[]){0xC3}, 1, 1}, + {0xA0, (uint8_t[]){0x09}, 1, 0}, + {0xF1, (uint8_t[]){0x10}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0x2A, (uint8_t[]){0x00, 0x00, 0x01, 0x67}, 4, 0}, + {0x2B, (uint8_t[]){0x01, 0x68, 0x01, 0x68}, 4, 0}, + {0x4D, (uint8_t[]){0x00}, 1, 0}, + {0x4E, (uint8_t[]){0x00}, 1, 0}, + {0x4F, (uint8_t[]){0x00}, 1, 0}, + {0x4C, (uint8_t[]){0x01}, 1, 10}, + {0x4C, (uint8_t[]){0x00}, 1, 0}, + {0x2A, (uint8_t[]){0x00, 0x00, 0x01, 0x67}, 4, 0}, + {0x2B, (uint8_t[]){0x00, 0x00, 0x01, 0x67}, 4, 0}, + {0x21, (uint8_t[]){0x00}, 1, 0}, + //{0x3A, (uint8_t[]){0x55}, 1, 0}, // color=16 + {0x11, (uint8_t[]){0x00}, 1, 120}, + {0x29, (uint8_t[]){0x00}, 1, 0}, +#else + {0xF0, (uint8_t[]){0x28}, 1, 0}, + {0xF2, (uint8_t[]){0x28}, 1, 0}, + {0x73, (uint8_t[]){0xF0}, 1, 0}, + {0x7C, (uint8_t[]){0xD1}, 1, 0}, + {0x83, (uint8_t[]){0xE0}, 1, 0}, + {0x84, (uint8_t[]){0x61}, 1, 0}, + {0xF2, (uint8_t[]){0x82}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0xF0, (uint8_t[]){0x01}, 1, 0}, + {0xF1, (uint8_t[]){0x01}, 1, 0}, + {0xB0, (uint8_t[]){0x56}, 1, 0}, + {0xB1, (uint8_t[]){0x4D}, 1, 0}, + {0xB2, (uint8_t[]){0x24}, 1, 0}, + {0xB4, (uint8_t[]){0x87}, 1, 0}, + {0xB5, (uint8_t[]){0x44}, 1, 0}, + {0xB6, (uint8_t[]){0x8B}, 1, 0}, + {0xB7, (uint8_t[]){0x40}, 1, 0}, + {0xB8, (uint8_t[]){0x86}, 1, 0}, + {0xBA, (uint8_t[]){0x00}, 1, 0}, + {0xBB, (uint8_t[]){0x08}, 1, 0}, + {0xBC, (uint8_t[]){0x08}, 1, 0}, + {0xBD, (uint8_t[]){0x00}, 1, 0}, + {0xC0, (uint8_t[]){0x80}, 1, 0}, + {0xC1, (uint8_t[]){0x10}, 1, 0}, + {0xC2, (uint8_t[]){0x37}, 1, 0}, + {0xC3, (uint8_t[]){0x80}, 1, 0}, + {0xC4, (uint8_t[]){0x10}, 1, 0}, + {0xC5, (uint8_t[]){0x37}, 1, 0}, + {0xC6, (uint8_t[]){0xA9}, 1, 0}, + {0xC7, (uint8_t[]){0x41}, 1, 0}, + {0xC8, (uint8_t[]){0x01}, 1, 0}, + {0xC9, (uint8_t[]){0xA9}, 1, 0}, + {0xCA, (uint8_t[]){0x41}, 1, 0}, + {0xCB, (uint8_t[]){0x01}, 1, 0}, + {0xD0, (uint8_t[]){0x91}, 1, 0}, + {0xD1, (uint8_t[]){0x68}, 1, 0}, + {0xD2, (uint8_t[]){0x68}, 1, 0}, + {0xF5, (uint8_t[]){0x00, 0xA5}, 2, 0}, + {0xDD, (uint8_t[]){0x4F}, 1, 0}, + {0xDE, (uint8_t[]){0x4F}, 1, 0}, + {0xF1, (uint8_t[]){0x10}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0xF0, (uint8_t[]){0x02}, 1, 0}, + {0xE0, (uint8_t[]){0xF0, 0x0A, 0x10, 0x09, 0x09, 0x36, 0x35, 0x33, 0x4A, 0x29, 0x15, 0x15, 0x2E, 0x34}, 14, 0}, + {0xE1, (uint8_t[]){0xF0, 0x0A, 0x0F, 0x08, 0x08, 0x05, 0x34, 0x33, 0x4A, 0x39, 0x15, 0x15, 0x2D, 0x33}, 14, 0}, + {0xF0, (uint8_t[]){0x10}, 1, 0}, + {0xF3, (uint8_t[]){0x10}, 1, 0}, + {0xE0, (uint8_t[]){0x07}, 1, 0}, + {0xE1, (uint8_t[]){0x00}, 1, 0}, + {0xE2, (uint8_t[]){0x00}, 1, 0}, + {0xE3, (uint8_t[]){0x00}, 1, 0}, + {0xE4, (uint8_t[]){0xE0}, 1, 0}, + {0xE5, (uint8_t[]){0x06}, 1, 0}, + {0xE6, (uint8_t[]){0x21}, 1, 0}, + {0xE7, (uint8_t[]){0x01}, 1, 0}, + {0xE8, (uint8_t[]){0x05}, 1, 0}, + {0xE9, (uint8_t[]){0x02}, 1, 0}, + {0xEA, (uint8_t[]){0xDA}, 1, 0}, + {0xEB, (uint8_t[]){0x00}, 1, 0}, + {0xEC, (uint8_t[]){0x00}, 1, 0}, + {0xED, (uint8_t[]){0x0F}, 1, 0}, + {0xEE, (uint8_t[]){0x00}, 1, 0}, + {0xEF, (uint8_t[]){0x00}, 1, 0}, + {0xF8, (uint8_t[]){0x00}, 1, 0}, + {0xF9, (uint8_t[]){0x00}, 1, 0}, + {0xFA, (uint8_t[]){0x00}, 1, 0}, + {0xFB, (uint8_t[]){0x00}, 1, 0}, + {0xFC, (uint8_t[]){0x00}, 1, 0}, + {0xFD, (uint8_t[]){0x00}, 1, 0}, + {0xFE, (uint8_t[]){0x00}, 1, 0}, + {0xFF, (uint8_t[]){0x00}, 1, 0}, + {0x60, (uint8_t[]){0x40}, 1, 0}, + {0x61, (uint8_t[]){0x04}, 1, 0}, + {0x62, (uint8_t[]){0x00}, 1, 0}, + {0x63, (uint8_t[]){0x42}, 1, 0}, + {0x64, (uint8_t[]){0xD9}, 1, 0}, + {0x65, (uint8_t[]){0x00}, 1, 0}, + {0x66, (uint8_t[]){0x00}, 1, 0}, + {0x67, (uint8_t[]){0x00}, 1, 0}, + {0x68, (uint8_t[]){0x00}, 1, 0}, + {0x69, (uint8_t[]){0x00}, 1, 0}, + {0x6A, (uint8_t[]){0x00}, 1, 0}, + {0x6B, (uint8_t[]){0x00}, 1, 0}, + {0x70, (uint8_t[]){0x40}, 1, 0}, + {0x71, (uint8_t[]){0x03}, 1, 0}, + {0x72, (uint8_t[]){0x00}, 1, 0}, + {0x73, (uint8_t[]){0x42}, 1, 0}, + {0x74, (uint8_t[]){0xD8}, 1, 0}, + {0x75, (uint8_t[]){0x00}, 1, 0}, + {0x76, (uint8_t[]){0x00}, 1, 0}, + {0x77, (uint8_t[]){0x00}, 1, 0}, + {0x78, (uint8_t[]){0x00}, 1, 0}, + {0x79, (uint8_t[]){0x00}, 1, 0}, + {0x7A, (uint8_t[]){0x00}, 1, 0}, + {0x7B, (uint8_t[]){0x00}, 1, 0}, + {0x80, (uint8_t[]){0x48}, 1, 0}, + {0x81, (uint8_t[]){0x00}, 1, 0}, + {0x82, (uint8_t[]){0x06}, 1, 0}, + {0x83, (uint8_t[]){0x02}, 1, 0}, + {0x84, (uint8_t[]){0xD6}, 1, 0}, + {0x85, (uint8_t[]){0x04}, 1, 0}, + {0x86, (uint8_t[]){0x00}, 1, 0}, + {0x87, (uint8_t[]){0x00}, 1, 0}, + {0x88, (uint8_t[]){0x48}, 1, 0}, + {0x89, (uint8_t[]){0x00}, 1, 0}, + {0x8A, (uint8_t[]){0x08}, 1, 0}, + {0x8B, (uint8_t[]){0x02}, 1, 0}, + {0x8C, (uint8_t[]){0xD8}, 1, 0}, + {0x8D, (uint8_t[]){0x04}, 1, 0}, + {0x8E, (uint8_t[]){0x00}, 1, 0}, + {0x8F, (uint8_t[]){0x00}, 1, 0}, + {0x90, (uint8_t[]){0x48}, 1, 0}, + {0x91, (uint8_t[]){0x00}, 1, 0}, + {0x92, (uint8_t[]){0x0A}, 1, 0}, + {0x93, (uint8_t[]){0x02}, 1, 0}, + {0x94, (uint8_t[]){0xDA}, 1, 0}, + {0x95, (uint8_t[]){0x04}, 1, 0}, + {0x96, (uint8_t[]){0x00}, 1, 0}, + {0x97, (uint8_t[]){0x00}, 1, 0}, + {0x98, (uint8_t[]){0x48}, 1, 0}, + {0x99, (uint8_t[]){0x00}, 1, 0}, + {0x9A, (uint8_t[]){0x0C}, 1, 0}, + {0x9B, (uint8_t[]){0x02}, 1, 0}, + {0x9C, (uint8_t[]){0xDC}, 1, 0}, + {0x9D, (uint8_t[]){0x04}, 1, 0}, + {0x9E, (uint8_t[]){0x00}, 1, 0}, + {0x9F, (uint8_t[]){0x00}, 1, 0}, + {0xA0, (uint8_t[]){0x48}, 1, 0}, + {0xA1, (uint8_t[]){0x00}, 1, 0}, + {0xA2, (uint8_t[]){0x05}, 1, 0}, + {0xA3, (uint8_t[]){0x02}, 1, 0}, + {0xA4, (uint8_t[]){0xD5}, 1, 0}, + {0xA5, (uint8_t[]){0x04}, 1, 0}, + {0xA6, (uint8_t[]){0x00}, 1, 0}, + {0xA7, (uint8_t[]){0x00}, 1, 0}, + {0xA8, (uint8_t[]){0x48}, 1, 0}, + {0xA9, (uint8_t[]){0x00}, 1, 0}, + {0xAA, (uint8_t[]){0x07}, 1, 0}, + {0xAB, (uint8_t[]){0x02}, 1, 0}, + {0xAC, (uint8_t[]){0xD7}, 1, 0}, + {0xAD, (uint8_t[]){0x04}, 1, 0}, + {0xAE, (uint8_t[]){0x00}, 1, 0}, + {0xAF, (uint8_t[]){0x00}, 1, 0}, + {0xB0, (uint8_t[]){0x48}, 1, 0}, + {0xB1, (uint8_t[]){0x00}, 1, 0}, + {0xB2, (uint8_t[]){0x09}, 1, 0}, + {0xB3, (uint8_t[]){0x02}, 1, 0}, + {0xB4, (uint8_t[]){0xD9}, 1, 0}, + {0xB5, (uint8_t[]){0x04}, 1, 0}, + {0xB6, (uint8_t[]){0x00}, 1, 0}, + {0xB7, (uint8_t[]){0x00}, 1, 0}, + {0xB8, (uint8_t[]){0x48}, 1, 0}, + {0xB9, (uint8_t[]){0x00}, 1, 0}, + {0xBA, (uint8_t[]){0x0B}, 1, 0}, + {0xBB, (uint8_t[]){0x02}, 1, 0}, + {0xBC, (uint8_t[]){0xDB}, 1, 0}, + {0xBD, (uint8_t[]){0x04}, 1, 0}, + {0xBE, (uint8_t[]){0x00}, 1, 0}, + {0xBF, (uint8_t[]){0x00}, 1, 0}, + {0xC0, (uint8_t[]){0x10}, 1, 0}, + {0xC1, (uint8_t[]){0x47}, 1, 0}, + {0xC2, (uint8_t[]){0x56}, 1, 0}, + {0xC3, (uint8_t[]){0x65}, 1, 0}, + {0xC4, (uint8_t[]){0x74}, 1, 0}, + {0xC5, (uint8_t[]){0x88}, 1, 0}, + {0xC6, (uint8_t[]){0x99}, 1, 0}, + {0xC7, (uint8_t[]){0x01}, 1, 0}, + {0xC8, (uint8_t[]){0xBB}, 1, 0}, + {0xC9, (uint8_t[]){0xAA}, 1, 0}, + {0xD0, (uint8_t[]){0x10}, 1, 0}, + {0xD1, (uint8_t[]){0x47}, 1, 0}, + {0xD2, (uint8_t[]){0x56}, 1, 0}, + {0xD3, (uint8_t[]){0x65}, 1, 0}, + {0xD4, (uint8_t[]){0x74}, 1, 0}, + {0xD5, (uint8_t[]){0x88}, 1, 0}, + {0xD6, (uint8_t[]){0x99}, 1, 0}, + {0xD7, (uint8_t[]){0x01}, 1, 0}, + {0xD8, (uint8_t[]){0xBB}, 1, 0}, + {0xD9, (uint8_t[]){0xAA}, 1, 0}, + {0xF3, (uint8_t[]){0x01}, 1, 0}, + {0xF0, (uint8_t[]){0x00}, 1, 0}, + {0x21, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 1, 120}, + {0x29, (uint8_t[]){0x00}, 1, 0}, +#endif +}; + +class Cst816s : public I2cDevice { +public: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + Cst816s(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA3); + ESP_LOGI(TAG, "Get chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; + } + + ~Cst816s() { + delete[] read_buffer_; + } + + void UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + } + + const TouchPoint_t& GetTouchPoint() { + return tp_; + } + +private: + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; +}; + +class TaijiPiS3Board : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Cst816s* cst816s_; + LcdDisplay* display_; + esp_timer_handle_t touchpad_timer_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = TP_PIN_NUM_TP_SDA, + .scl_io_num = TP_PIN_NUM_TP_SCL, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static void touchpad_timer_callback(void* arg) { + auto& board = (TaijiPiS3Board&)Board::GetInstance(); + auto touchpad = board.GetTouchpad(); + static bool was_touched = false; + static int64_t touch_start_time = 0; + const int64_t TOUCH_THRESHOLD_MS = 500; // 触摸时长阈值,超过500ms视为长按 + + touchpad->UpdateTouchPoint(); + auto touch_point = touchpad->GetTouchPoint(); + + // 检测触摸开始 + if (touch_point.num > 0 && !was_touched) { + was_touched = true; + touch_start_time = esp_timer_get_time() / 1000; // 转换为毫秒 + } + // 检测触摸释放 + else if (touch_point.num == 0 && was_touched) { + was_touched = false; + int64_t touch_duration = (esp_timer_get_time() / 1000) - touch_start_time; + + // 只有短触才触发 + if (touch_duration < TOUCH_THRESHOLD_MS) { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && + !WifiStation::GetInstance().IsConnected()) { + board.ResetWifiConfiguration(); + } + app.ToggleChatState(); + } + } + } + + void InitializeCst816sTouchPad() { + ESP_LOGI(TAG, "Init Cst816s"); + cst816s_ = new Cst816s(i2c_bus_, 0x15); + + // 创建定时器,10ms 间隔 + esp_timer_create_args_t timer_args = { + .callback = touchpad_timer_callback, + .arg = NULL, + .dispatch_method = ESP_TIMER_TASK, + .name = "touchpad_timer", + .skip_unhandled_events = true, + }; + + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &touchpad_timer_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(touchpad_timer_, 10 * 1000)); // 10ms = 10000us + } + + void BspLcdBlSet(int brightness_percent) + { + if (brightness_percent > 100) { + brightness_percent = 100; + } + if (brightness_percent < 0) { + brightness_percent = 0; + } + + ESP_LOGI(TAG, "Setting LCD backlight: %d%%", brightness_percent); + uint32_t duty_cycle = (1023 * brightness_percent) / 100; // LEDC resolution set to 10bits, thus: 100% = 1023 + ledc_set_duty(LEDC_LOW_SPEED_MODE, LEDC_CHANNEL_0, duty_cycle); + ledc_update_duty(LEDC_LOW_SPEED_MODE, LEDC_CHANNEL_0); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + + const spi_bus_config_t bus_config = TAIJIPI_ST77916_PANEL_BUS_QSPI_CONFIG(QSPI_PIN_NUM_LCD_PCLK, + QSPI_PIN_NUM_LCD_DATA0, + QSPI_PIN_NUM_LCD_DATA1, + QSPI_PIN_NUM_LCD_DATA2, + QSPI_PIN_NUM_LCD_DATA3, + QSPI_LCD_H_RES * 80 * sizeof(uint16_t)); + ESP_ERROR_CHECK(spi_bus_initialize(QSPI_LCD_HOST, &bus_config, SPI_DMA_CH_AUTO)); + } + + void Initializest77916Display() { + + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + ESP_LOGI(TAG, "Install panel IO"); + + const esp_lcd_panel_io_spi_config_t io_config = ST77916_PANEL_IO_QSPI_CONFIG(QSPI_PIN_NUM_LCD_CS, NULL, NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)QSPI_LCD_HOST, &io_config, &panel_io)); + + ESP_LOGI(TAG, "Install ST77916 panel driver"); + + st77916_vendor_config_t vendor_config = { + .init_cmds = lcd_init_cmds, // 如果使用自定义初始化命令,请取消注释这些行 + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(st77916_lcd_init_cmd_t), + .flags = { + .use_qspi_interface = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = QSPI_PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, // Implemented by LCD command `36h` + .bits_per_pixel = QSPI_LCD_BIT_PER_PIXEL, // Implemented by LCD command `3Ah` (16/18) + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st77916(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_disp_on_off(panel, true); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeMute() { + gpio_reset_pin(AUDIO_MUTE_PIN); + /* Set the GPIO as a push/pull output */ + gpio_set_direction(AUDIO_MUTE_PIN, GPIO_MODE_OUTPUT); + gpio_set_level(AUDIO_MUTE_PIN, 1); + } + +public: + TaijiPiS3Board() { + InitializeI2c(); + InitializeCst816sTouchPad(); + InitializeSpi(); + Initializest77916Display(); + InitializeMute(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { +#ifdef CONFIG_TAIJIPAI_I2S_TYPE_STD + static NoAudioCodecSimplex audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + #ifdef CONFIG_I2S_USE_2SLOT + I2S_STD_SLOT_BOTH, + #endif + AUDIO_MIC_SCK_PIN, + AUDIO_MIC_WS_PIN, + #ifdef CONFIG_I2S_USE_2SLOT + AUDIO_MIC_SD_PIN, + I2S_STD_SLOT_LEFT + #else + AUDIO_MIC_SD_PIN + #endif + ); +#else + static NoAudioCodecSimplexPdm audio_codec( + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + #ifdef CONFIG_I2S_USE_2SLOT + I2S_STD_SLOT_BOTH, + #endif + AUDIO_MIC_WS_PIN, + AUDIO_MIC_SD_PIN + ); +#endif + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst816s* GetTouchpad() { + return cst816s_; + } +}; + +DECLARE_BOARD(TaijiPiS3Board); diff --git a/main/boards/tudouzi/config.h b/main/boards/tudouzi/config.h new file mode 100644 index 0000000..a272900 --- /dev/null +++ b/main/boards/tudouzi/config.h @@ -0,0 +1,41 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_40 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_47 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_48 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_9 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_42 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_41 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_3 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_1 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_2 + +#define DISPLAY_SDA_PIN GPIO_NUM_7 +#define DISPLAY_SCL_PIN GPIO_NUM_8 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define ML307_RX_PIN GPIO_NUM_5 +#define ML307_TX_PIN GPIO_NUM_6 + +#define AXP2101_I2C_ADDR 0x34 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/tudouzi/config.json b/main/boards/tudouzi/config.json new file mode 100644 index 0000000..d9eee68 --- /dev/null +++ b/main/boards/tudouzi/config.json @@ -0,0 +1,13 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "tudouzi", + "sdkconfig_append": [ + "CONFIG_USE_WAKE_WORD_DETECT=n", + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/tudouzi/kevin_box_board.cc b/main/boards/tudouzi/kevin_box_board.cc new file mode 100644 index 0000000..d6cb5b2 --- /dev/null +++ b/main/boards/tudouzi/kevin_box_board.cc @@ -0,0 +1,255 @@ +#include "ml307_board.h" +#include "codecs/box_audio_codec.h" +#include "display/oled_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include + +#define TAG "KevinBoxBoard" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + // ** EFUSE defaults ** + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + WriteReg(0x93, 0x1C); // 配置 aldo2 输出为 3.3V + + uint8_t value = ReadReg(0x90); // XPOWERS_AXP2101_LDO_ONOFF_CTRL0 + value = value | 0x02; // set bit 1 (ALDO2) + WriteReg(0x90, value); // and power channels now enabled + + WriteReg(0x64, 0x03); // CV charger voltage setting to 4.2V + + WriteReg(0x61, 0x05); // set Main battery precharge current to 125mA + WriteReg(0x62, 0x0A); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x15); // set Main battery term charge current to 125mA + + WriteReg(0x14, 0x00); // set minimum system voltage to 4.1V (default 4.7V), for poor USB cables + WriteReg(0x15, 0x00); // set input voltage limit to 3.88v, for poor USB cables + WriteReg(0x16, 0x05); // set input current limit to 2000mA + + WriteReg(0x24, 0x01); // set Vsys for PWROFF threshold to 3.2V (default - 2.6V and kill battery) + WriteReg(0x50, 0x14); // set TS pin to EXTERNAL input (not temperature) + } +}; + +class KevinBoxBoard : public Ml307Board { +private: + i2c_master_bus_handle_t display_i2c_bus_; + i2c_master_bus_handle_t codec_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Pmic* pmic_ = nullptr; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(240, 60, -1); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->SetEnabled(true); + } + + void Enable4GModule() { + // Make GPIO HIGH to enable the 4G module + gpio_config_t ml307_enable_config = { + .pin_bit_mask = (1ULL << 4), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + gpio_config(&ml307_enable_config); + gpio_set_level(GPIO_NUM_4, 1); + } + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeButtons() { + boot_button_.OnPressDown([this]() { + power_save_timer_->WakeUp(); + Application::GetInstance().StartListening(); + }); + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + +public: + KevinBoxBoard() : Ml307Board(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeCodecI2c(); + pmic_ = new Pmic(codec_i2c_bus_, AXP2101_I2C_ADDR); + + Enable4GModule(); + + InitializeButtons(); + InitializePowerSaveTimer(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec(codec_i2c_bus_, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR, AUDIO_CODEC_ES7210_ADDR, AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } +}; + +DECLARE_BOARD(KevinBoxBoard); \ No newline at end of file diff --git a/main/boards/waveshare-c6-lcd-1.69/README.md b/main/boards/waveshare-c6-lcd-1.69/README.md new file mode 100644 index 0000000..5a44c06 --- /dev/null +++ b/main/boards/waveshare-c6-lcd-1.69/README.md @@ -0,0 +1,56 @@ +# 产品链接 + +[微雪电子 ESP32-C6-Touch-LCD-1.69](https://www.waveshare.net/shop/ESP32-C6-Touch-LCD-1.69.htm) +[微雪电子 ESP32-C6-LCD-1.69](https://www.waveshare.net/shop/ESP32-C6-LCD-1.69.htm) + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32C6** + +```bash +idf.py set-target esp32c6 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +Xiaozhi Assistant -> Board Type -> Waveshare ESP32-C6-LCD-1.69 +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` +# 按键操作 +## BOOT 按键 +**未连接服务器前单击: 进入配网模式** +**连接服务器后单击: 唤醒、打断** + +## PWR 按键 +**双击:息屏、亮屏** +**长按:开关机** \ No newline at end of file diff --git a/main/boards/waveshare-c6-lcd-1.69/config.h b/main/boards/waveshare-c6-lcd-1.69/config.h new file mode 100644 index 0000000..0904631 --- /dev/null +++ b/main/boards/waveshare-c6-lcd-1.69/config.h @@ -0,0 +1,54 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_19 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_22 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_20 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_21 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_23 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_9 +#define PWR_BUTTON_GPIO GPIO_NUM_18 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SPI_MODE 3 +#define DISPLAY_CS_PIN GPIO_NUM_5 +#define DISPLAY_MOSI_PIN GPIO_NUM_2 +#define DISPLAY_MISO_PIN GPIO_NUM_NC +#define DISPLAY_CLK_PIN GPIO_NUM_1 +#define DISPLAY_DC_PIN GPIO_NUM_3 +#define DISPLAY_RST_PIN GPIO_NUM_4 + +#define BATTERY_EN_PIN GPIO_NUM_15 +#define BATTERY_ADC_PIN GPIO_NUM_0 +#define BATTERY_CHARGING_PIN GPIO_NUM_NC + + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 280 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_INVERT_COLOR true + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 20 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_6 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-c6-lcd-1.69/config.json b/main/boards/waveshare-c6-lcd-1.69/config.json new file mode 100644 index 0000000..81dc2b1 --- /dev/null +++ b/main/boards/waveshare-c6-lcd-1.69/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32c6", + "builds": [ + { + "name": "waveshare-c6-lcd-1.69", + "sdkconfig_append": [ + "CONFIG_USE_ESP_WAKE_WORD=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-c6-lcd-1.69/esp32-c6-lcd-1.69.cc b/main/boards/waveshare-c6-lcd-1.69/esp32-c6-lcd-1.69.cc new file mode 100644 index 0000000..bebe974 --- /dev/null +++ b/main/boards/waveshare-c6-lcd-1.69/esp32-c6-lcd-1.69.cc @@ -0,0 +1,254 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include +#include +#include "iot_button.h" +#include "power_manager.h" +#include "power_save_timer.h" + +#define TAG "waveshare_lcd_1_69" + +class CustomLcdDisplay : public SpiLcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES * 0.1, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES * 0.1, 0); + } +}; + +class CustomButton: public Button { +public: + void OnPressDownDel(void) { + if (button_handle_ == nullptr) { + return; + } + on_press_down_ = NULL; + iot_button_unregister_cb(button_handle_, BUTTON_PRESS_DOWN, nullptr); + } + void OnPressUpDel(void) { + if (button_handle_ == nullptr) { + return; + } + on_press_up_ = NULL; + iot_button_unregister_cb(button_handle_, BUTTON_PRESS_UP, nullptr); + } +}; + +class CustomBoard : public WifiBoard { +private: + CustomButton boot_button_; + CustomButton pwr_button_; + i2c_master_bus_handle_t i2c_bus_; + LcdDisplay* display_; + PowerManager* power_manager_ = nullptr; + PowerSaveTimer* power_save_timer_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(BATTERY_CHARGING_PIN, BATTERY_ADC_PIN, BATTERY_EN_PIN); + power_manager_->PowerON(); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->OnShutdownRequest([this]() { + power_manager_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = DISPLAY_MISO_PIN; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = DISPLAY_SPI_MODE; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGI(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new CustomLcdDisplay( + panel_io, + panel, + DISPLAY_WIDTH, + DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, + DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, + DISPLAY_SWAP_XY + ); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + pwr_button_.OnPressUp([this]() { + pwr_button_.OnDoubleClick([this]() { + static uint8_t brightness_last = 0; + auto backlight = Board::GetInstance().GetBacklight(); + if (backlight->brightness() == 0) { + brightness_last = 0; + if (brightness_last == 0) { + backlight->SetBrightness(50, true); + } else { + backlight->SetBrightness(brightness_last, true); + } + } else { + brightness_last = backlight->brightness(); + backlight->SetBrightness(0); + } + }); + + pwr_button_.OnLongPress([this]() { + // printf("Power button long press\n"); + if (power_manager_ != nullptr){ + power_manager_->PowerOff(); + } + }); + + pwr_button_.OnPressUpDel(); + }); + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO), pwr_button_(PWR_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/waveshare-c6-lcd-1.69/power_manager.h b/main/boards/waveshare-c6-lcd-1.69/power_manager.h new file mode 100644 index 0000000..adb7bee --- /dev/null +++ b/main/boards/waveshare-c6-lcd-1.69/power_manager.h @@ -0,0 +1,174 @@ +#pragma once +#include +#include +#include +#include +#include +#include "esp_adc/adc_oneshot.h" +#include "esp_adc/adc_cali.h" +#include "esp_adc/adc_cali_scheme.h" +#include + + +class PowerManager { +private: + gpio_num_t charging_pin_ = GPIO_NUM_NC; + gpio_num_t bat_adc_pin_ = GPIO_NUM_NC; + gpio_num_t bat_power_pin_ = GPIO_NUM_NC; + adc_oneshot_unit_handle_t adc_handle_ = NULL; + adc_cali_handle_t adc_cali_handle_ = NULL; + adc_channel_t adc_channel_; + bool do_calibration = false; + + bool adc_calibration_init(adc_unit_t unit, adc_channel_t channel, adc_atten_t atten, adc_cali_handle_t *out_handle) { + adc_cali_handle_t handle = NULL; + esp_err_t ret = ESP_FAIL; + bool calibrated = false; + + if (!calibrated) { + ESP_LOGI("PowerManager", "calibration scheme version is %s", "Curve Fitting"); + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = unit, + .chan = channel, + .atten = atten, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + ret = adc_cali_create_scheme_curve_fitting(&cali_config, &handle); + if (ret == ESP_OK) { + calibrated = true; + } + } + + *out_handle = handle; + if (ret == ESP_OK) { + ESP_LOGI("PowerManager", "Calibration Success"); + } + else if (ret == ESP_ERR_NOT_SUPPORTED || !calibrated) { + ESP_LOGW("PowerManager", "eFuse not burnt, skip software calibration"); + } + else { + ESP_LOGE("PowerManager", "Invalid arg or no memory"); + } + return calibrated; + } + +public: + PowerManager(gpio_num_t charging_pin, gpio_num_t bat_adc_pin, gpio_num_t bat_power_pin) + : charging_pin_(charging_pin), bat_adc_pin_(bat_adc_pin), bat_power_pin_(bat_power_pin) { + // 初始化充电引脚 + if (charging_pin_ != GPIO_NUM_NC) { + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = 1ULL << charging_pin_; + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + gpio_config(&io_conf); + } + + // 初始化电池使能引脚 + if (bat_power_pin_ != GPIO_NUM_NC) { + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << bat_power_pin_; + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + } + + // 初始化adc + if (bat_adc_pin_ != GPIO_NUM_NC) { + adc_oneshot_unit_init_cfg_t init_config = {}; + init_config.ulp_mode = ADC_ULP_MODE_DISABLE; + init_config.unit_id = ADC_UNIT_1; + + if (bat_adc_pin_ >= GPIO_NUM_0 && bat_adc_pin_ <= GPIO_NUM_6) + adc_channel_ = (adc_channel_t)((int)bat_adc_pin_); + else + return; + + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + adc_oneshot_chan_cfg_t config = {}; + config.bitwidth = ADC_BITWIDTH_DEFAULT; + config.atten = ADC_ATTEN_DB_12; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, adc_channel_, &config)); + do_calibration = adc_calibration_init(init_config.unit_id, adc_channel_, config.atten, &adc_cali_handle_); + } + } + + ~PowerManager() { + if (adc_handle_) { + ESP_ERROR_CHECK(adc_oneshot_del_unit(adc_handle_)); + } + } + + int GetBatteryLevel(void) { + int adc_raw = 0; + int voltage_int = 0; + const float voltage_float_threshold = 0.1f; + float voltage_float = 0.0f; + static float last_voltage_float = 0.0f; + static int last_battery_level = 0; + + if (adc_handle_ != nullptr) { + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, adc_channel_, &adc_raw)); + if (do_calibration) { + ESP_ERROR_CHECK(adc_cali_raw_to_voltage(adc_cali_handle_, adc_raw, &voltage_int)); + voltage_float = (voltage_int / 1000.0f) * 3.0; + + if (fabs(voltage_float - last_voltage_float) >= voltage_float_threshold) { + last_voltage_float = voltage_float; + if (voltage_float < 3.52) { + last_battery_level = 1; + } else if (voltage_float < 3.64) { + last_battery_level = 20; + } else if (voltage_float < 3.76) { + last_battery_level = 40; + } else if (voltage_float < 3.88) { + last_battery_level = 60; + } else if (voltage_float < 4.0) { + last_battery_level = 80; + } else { + last_battery_level = 100; + } + } + return last_battery_level; + } + } + return 100; + } + + bool IsCharging(void) { + if (charging_pin_ != GPIO_NUM_NC) { + return gpio_get_level(charging_pin_) == 0 ? true : false; + } + return false; + } + + bool IsDischarging(void) { + if (charging_pin_ != GPIO_NUM_NC) { + return gpio_get_level(charging_pin_) == 1; + } + return true; + } + + bool IsChargingDone(void) { + if (GetBatteryLevel() == 100) { + return true; + } + return false; + } + + void PowerOff(void) { + if (bat_power_pin_ != GPIO_NUM_NC) { + gpio_set_level(bat_power_pin_, 0); + } + } + + void PowerON(void) { + if (bat_power_pin_ != GPIO_NUM_NC) { + gpio_set_level(bat_power_pin_, 1); + } + } +}; diff --git a/main/boards/waveshare-c6-touch-amoled-1.32/README.md b/main/boards/waveshare-c6-touch-amoled-1.32/README.md new file mode 100644 index 0000000..c153ac1 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.32/README.md @@ -0,0 +1,48 @@ +# 产品链接 + +[微雪电子 ESP32-C6-Touch-AMOLED-1.32](https://www.waveshare.net/shop/ESP32-C6-Touch-AMOLED-1.32.htm) + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32C6** + +```bash +idf.py set-target esp32c6 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +Xiaozhi Assistant -> Board Type -> Waveshare ESP32-C6-Touch-AMOLED-1.32 +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` + diff --git a/main/boards/waveshare-c6-touch-amoled-1.32/config.h b/main/boards/waveshare-c6-touch-amoled-1.32/config.h new file mode 100644 index 0000000..70a5301 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.32/config.h @@ -0,0 +1,44 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_15 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_5 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_3 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_4 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_6 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_23 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + + +#define LCD_CS GPIO_NUM_22 +#define LCD_PCLK GPIO_NUM_18 +#define LCD_D0 GPIO_NUM_19 +#define LCD_D1 GPIO_NUM_20 +#define LCD_D2 GPIO_NUM_10 +#define LCD_D3 GPIO_NUM_11 +#define LCD_RST GPIO_NUM_21 + +#define EXAMPLE_LCD_H_RES 466 +#define EXAMPLE_LCD_V_RES 466 + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define SYS_POWER_IO_PIN GPIO_NUM_2 +#define PWR_KEY_GPIO GPIO_NUM_1 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-c6-touch-amoled-1.32/config.json b/main/boards/waveshare-c6-touch-amoled-1.32/config.json new file mode 100644 index 0000000..73dac1d --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.32/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32c6", + "builds": [ + { + "name": "waveshare-c6-touch-amoled-1.32", + "sdkconfig_append": [ + "CONFIG_USE_ESP_WAKE_WORD=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-c6-touch-amoled-1.32/esp32-c6-touch-amoled-1.32.cc b/main/boards/waveshare-c6-touch-amoled-1.32/esp32-c6-touch-amoled-1.32.cc new file mode 100644 index 0000000..4c5516e --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.32/esp32-c6-touch-amoled-1.32.cc @@ -0,0 +1,214 @@ +#include "application.h" +#include "button.h" +#include "codecs/es8311_audio_codec.h" +#include "config.h" +#include "wifi_board.h" + +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" +#include "lvgl.h" +#include "mcp_server.h" +#include +#include +#include +#include +#include + +#define TAG "waveshare_c6_amoled_1_32" + +static const sh8601_lcd_init_cmd_t lcd_init_cmds[] = { + {0xFE, (uint8_t[]) {0x00}, 1, 0}, + {0xC4, (uint8_t[]) {0x80}, 1, 0}, + {0x3A, (uint8_t[]) {0x55}, 1, 0}, // 0x55 for RGB565, 0x77 for RGB888 + {0x35, (uint8_t[]) {0x00}, 1, 0}, + {0x53, (uint8_t[]) {0x20}, 1, 0}, + {0x51, (uint8_t[]) {0xFF}, 1, 0}, // Brightness + {0x63, (uint8_t[]) {0xFF}, 1, 0}, + {0x2A, (uint8_t[]) {0x00, 0x06, 0x01, 0xD7}, 4, 0}, + {0x2B, (uint8_t[]) {0x00, 0x00, 0x01, 0xD1}, 4, 0}, + {0x11, (uint8_t[]) {0x00}, 0, 100}, + {0x29, (uint8_t[]) {0x00}, 0, 0}, +}; + +class CustomLcdDisplay : public SpiLcdDisplay { + private: + esp_lcd_panel_io_handle_t io_handle_; + + public: + static void my_draw_event_cb(lv_event_t *e) { + lv_area_t *area = (lv_area_t *) lv_event_get_param(e); + + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + + // Round area for better performance + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + void SetMIRROR_XY(uint8_t mirror) { + uint32_t lcd_cmd = 0x36; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= 0x02 << 24; + uint8_t param = mirror; + esp_lcd_panel_io_tx_param(io_handle_, lcd_cmd, ¶m, 1); + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, esp_lcd_panel_handle_t panel_handle, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) : + SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy), + io_handle_(io_handle) { + DisplayLockGuard lock(this); + lv_display_add_event_cb(display_, my_draw_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + SetMIRROR_XY(0xC0); // Rotate 180 degrees + lv_obj_invalidate(lv_screen_active()); + } +}; + +class CustomBoard : public WifiBoard { + private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button pwr_button_; + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_io_handle_t io_handle = NULL; + CustomLcdDisplay *display_; + lv_indev_t *touch_indev = NULL; + i2c_master_dev_handle_t disp_touch_dev_handle = NULL; + + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = {}; + i2c_bus_cfg.i2c_port = I2C_NUM_0; + i2c_bus_cfg.sda_io_num = AUDIO_CODEC_I2C_SDA_PIN; + i2c_bus_cfg.scl_io_num = AUDIO_CODEC_I2C_SCL_PIN; + i2c_bus_cfg.clk_source = I2C_CLK_SRC_DEFAULT; + i2c_bus_cfg.glitch_ignore_cnt = 7; + i2c_bus_cfg.intr_priority = 0; + i2c_bus_cfg.trans_queue_depth = 0; + i2c_bus_cfg.flags.enable_internal_pullup = 1; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void SetDispbacklight(uint8_t backlight) { + uint32_t lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= 0x02 << 24; + uint8_t param = backlight; + esp_lcd_panel_io_tx_param(io_handle, lcd_cmd, ¶m, 1); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto &app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + pwr_button_.OnLongPress([this]() { + GetDisplay()->SetChatMessage("system", "OFF"); + vTaskDelay(pdMS_TO_TICKS(1000)); + gpio_set_level(SYS_POWER_IO_PIN, 0); + }); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.data0_io_num = LCD_D0; + buscfg.data1_io_num = LCD_D1; + buscfg.sclk_io_num = LCD_PCLK; + buscfg.data2_io_num = LCD_D2; + buscfg.data3_io_num = LCD_D3; + buscfg.max_transfer_sz = EXAMPLE_LCD_H_RES * EXAMPLE_LCD_V_RES * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS; + io_config.dc_gpio_num = -1; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 8; + io_config.on_color_trans_done = NULL; + io_config.user_ctx = NULL; + io_config.lcd_cmd_bits = 32; + io_config.lcd_param_bits = 8; + io_config.flags.quad_mode = true; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &io_handle)); + + sh8601_vendor_config_t vendor_config = {}; + vendor_config.init_cmds = lcd_init_cmds; + vendor_config.init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]); + vendor_config.flags = {.use_qspi_interface = 1}; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(io_handle, &panel_config, &panel_handle)); + esp_lcd_panel_set_gap(panel_handle, 0x06, 0x00); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + + display_ = new CustomLcdDisplay(io_handle, panel_handle, EXAMPLE_LCD_H_RES, EXAMPLE_LCD_V_RES, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.disp.setbacklight", "设置屏幕亮度", PropertyList({Property("level", kPropertyTypeInteger, 0, 255)}), [this](const PropertyList &properties) -> ReturnValue { + int level = properties["level"].value(); + ESP_LOGI("setbacklight", "%d", level); + SetDispbacklight(level); + return true; + }); + + mcp_server.AddTool("self.disp.network", "重新配网", PropertyList(), [this](const PropertyList &) -> ReturnValue { + ResetWifiConfiguration(); + return true; + }); + } + + void CheckPowerKeyState() { + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = (0x1ULL << SYS_POWER_IO_PIN); + gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_conf.pull_up_en = GPIO_PULLUP_ENABLE; + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + gpio_set_level(SYS_POWER_IO_PIN, 1); + do { + vTaskDelay(pdMS_TO_TICKS(10)); + } while (!gpio_get_level(PWR_KEY_GPIO)); + } + + public: + CustomBoard() : boot_button_(BOOT_BUTTON_GPIO), pwr_button_(PWR_KEY_GPIO) { + CheckPowerKeyState(); + InitializeI2c(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/waveshare-c6-touch-amoled-1.43/README.md b/main/boards/waveshare-c6-touch-amoled-1.43/README.md new file mode 100644 index 0000000..7703850 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.43/README.md @@ -0,0 +1,49 @@ +# 产品链接 + +[微雪电子 ESP32-C6-Touch-AMOLED-1.43](https://www.waveshare.net/shop/ESP32-C6-Touch-AMOLED-1.43.htm) +[微雪电子 ESP32-C6-Touch-AMOLED-1.43-B](https://www.waveshare.net/shop/ESP32-C6-Touch-AMOLED-1.43-B.htm) + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32C6** + +```bash +idf.py set-target esp32c6 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +Xiaozhi Assistant -> Board Type -> Waveshare ESP32-C6-Touch-AMOLED-1.43 +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` + diff --git a/main/boards/waveshare-c6-touch-amoled-1.43/config.h b/main/boards/waveshare-c6-touch-amoled-1.43/config.h new file mode 100644 index 0000000..0d39b3f --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.43/config.h @@ -0,0 +1,49 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE false + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_19 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_22 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_21 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_20 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_23 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_18 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define I2C_Touch_ADDRESS 0x38 +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 +#define BOOT_BUTTON_GPIO GPIO_NUM_9 +#define PWR_BUTTON_GPIO GPIO_NUM_2 + +#define LCD_CS GPIO_NUM_10 +#define LCD_PCLK GPIO_NUM_11 +#define LCD_D0 GPIO_NUM_4 +#define LCD_D1 GPIO_NUM_5 +#define LCD_D2 GPIO_NUM_6 +#define LCD_D3 GPIO_NUM_7 +#define LCD_RST GPIO_NUM_3 +#define LCD_LIGHT (-1) + +#define EXAMPLE_LCD_H_RES 466 +#define EXAMPLE_LCD_V_RES 466 + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-c6-touch-amoled-1.43/config.json b/main/boards/waveshare-c6-touch-amoled-1.43/config.json new file mode 100644 index 0000000..f1a4551 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.43/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32c6", + "builds": [ + { + "name": "waveshare-c6-touch-amoled-1.43", + "sdkconfig_append": [ + "CONFIG_USE_ESP_WAKE_WORD=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-c6-touch-amoled-1.43/esp32-c6-touch-amoled-1.43.cc b/main/boards/waveshare-c6-touch-amoled-1.43/esp32-c6-touch-amoled-1.43.cc new file mode 100644 index 0000000..42cd4b9 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-1.43/esp32-c6-touch-amoled-1.43.cc @@ -0,0 +1,284 @@ +#include "wifi_board.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "codecs/box_audio_codec.h" + +#include +#include +#include +#include +#include +#include "esp_lcd_sh8601.h" +#include "display/lcd_display.h" +#include "esp_io_expander_tca9554.h" +#include "mcp_server.h" +#include "lvgl.h" + +#define TAG "waveshare_c6_amoled_1_43" + +static const sh8601_lcd_init_cmd_t lcd_init_cmds[] = +{ + {0x11, (uint8_t []){0x00}, 0, 80}, + {0xC4, (uint8_t []){0x80}, 1, 0}, + {0x53, (uint8_t []){0x20}, 1, 1}, + {0x63, (uint8_t []){0xFF}, 1, 1}, + {0x51, (uint8_t []){0x00}, 1, 1}, + {0x29, (uint8_t []){0x00}, 0, 10}, + {0x51, (uint8_t []){0xFF}, 1, 0}, +}; + +class CustomLcdDisplay : public SpiLcdDisplay { +public: + static void MyDrawEventCb(lv_event_t *e) { + lv_area_t *area = (lv_area_t *)lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + // round the start of coordinate down to the nearest 2M number + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + // round the end of coordinate up to the nearest 2N+1 number + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_display_add_event_cb(display_, MyDrawEventCb, LV_EVENT_INVALIDATE_AREA, NULL); + } +}; + +class CustomBoard : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button pwr_button_; + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_io_handle_t io_handle = NULL; + esp_io_expander_handle_t io_expander = NULL; + CustomLcdDisplay* display_; + i2c_master_dev_handle_t disp_touch_dev_handle = NULL; + lv_indev_t *touch_indev = NULL; //touch + uint8_t pwr_flag = 0; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_7 | IO_EXPANDER_PIN_NUM_6, IO_EXPANDER_OUTPUT); + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_7 | IO_EXPANDER_PIN_NUM_6, 1); + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = { + .data0_io_num = LCD_D0, + .data1_io_num = LCD_D1, + .sclk_io_num = LCD_PCLK, + .data2_io_num = LCD_D2, + .data3_io_num = LCD_D3, + .max_transfer_sz = EXAMPLE_LCD_H_RES * EXAMPLE_LCD_V_RES * sizeof(uint16_t), + }; + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + const esp_lcd_panel_io_spi_config_t io_config = { + .cs_gpio_num = LCD_CS, + .dc_gpio_num = -1, + .spi_mode = 0, + .pclk_hz = 40 * 1000 * 1000, + .trans_queue_depth = 4, + .on_color_trans_done = NULL, + .user_ctx = NULL, + .lcd_cmd_bits = 32, + .lcd_param_bits = 8, + .flags = { + .quad_mode = true, + }, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &io_handle)); + sh8601_vendor_config_t vendor_config = { + .init_cmds = lcd_init_cmds, // Uncomment these line if use custom initialization commands + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]), // sizeof(axs15231b_lcd_init_cmd_t), + .flags = + { + .use_qspi_interface = 1, + }, + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, // Implemented by LCD command `36h` + .bits_per_pixel = 16, // Implemented by LCD command `3Ah` (16/18) + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(io_handle, &panel_config, &panel_handle)); + esp_lcd_panel_set_gap(panel_handle,0x06,0x00); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + display_ = new CustomLcdDisplay(io_handle, panel_handle, + EXAMPLE_LCD_H_RES, EXAMPLE_LCD_V_RES, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { //接入锂电池时,可长按PWR开机/关机 + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + }); + + boot_button_.OnPressDown([this]() { + Application::GetInstance().StartListening(); + }); + + boot_button_.OnPressUp([this]() { + Application::GetInstance().StopListening(); + }); + + pwr_button_.OnLongPress([this]() { + if(pwr_flag == 1) + { + pwr_flag = 0; + esp_err_t ret; + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_6, 0); + ESP_ERROR_CHECK(ret); + } + }); + + pwr_button_.OnPressUp([this]() { + if(pwr_flag == 0) + { + pwr_flag = 1; + } + }); + } + + void InitializeTouch() { + i2c_device_config_t dev_cfg = + { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = I2C_Touch_ADDRESS, + .scl_speed_hz = 300000, + }; + ESP_ERROR_CHECK(i2c_master_bus_add_device(i2c_bus_, &dev_cfg, &disp_touch_dev_handle)); + + touch_indev = lv_indev_create(); + lv_indev_set_type(touch_indev, LV_INDEV_TYPE_POINTER); + lv_indev_set_read_cb(touch_indev, TouchInputReadCallback); + lv_indev_set_user_data(touch_indev, disp_touch_dev_handle); + } + + static void TouchInputReadCallback(lv_indev_t * indev, lv_indev_data_t *indevData) + { + i2c_master_dev_handle_t i2c_dev = (i2c_master_dev_handle_t)lv_indev_get_user_data(indev); + uint8_t cmd = 0x02; + uint8_t buf[5] = {0}; + uint16_t tp_x,tp_y; + i2c_master_transmit_receive(i2c_dev,&cmd,1,buf,5,1000); + if(buf[0]) + { + tp_x = (((uint16_t)buf[1] & 0x0f)<<8) | (uint16_t)buf[2]; + tp_y = (((uint16_t)buf[3] & 0x0f)<<8) | (uint16_t)buf[4]; + if(tp_x > EXAMPLE_LCD_H_RES) + {tp_x = EXAMPLE_LCD_H_RES;} + if(tp_y > EXAMPLE_LCD_V_RES) + {tp_y = EXAMPLE_LCD_V_RES;} + indevData->point.x = tp_x; + indevData->point.y = tp_y; + //ESP_LOGI("tp","(%ld,%ld)",indevData->point.x,indevData->point.y); + indevData->state = LV_INDEV_STATE_PRESSED; + } + else + { + indevData->state = LV_INDEV_STATE_RELEASED; + } + } + + void InitializeTools() + { + auto& mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.disp.setbacklight", "设置屏幕亮度", PropertyList({ + Property("level", kPropertyTypeInteger, 0, 255) + }), [this](const PropertyList& properties) -> ReturnValue { + int level = properties["level"].value(); + ESP_LOGI("setbacklight","%d",level); + SetDispbacklight(level); + return true; + }); + } + + void SetDispbacklight(uint8_t backlight) { + uint32_t lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= 0x02 << 24; + uint8_t param = backlight; + esp_lcd_panel_io_tx_param(io_handle, lcd_cmd, ¶m,1); + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO),pwr_button_(PWR_BUTTON_GPIO) { + InitializeI2c(); + InitializeTca9554(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + +}; + +DECLARE_BOARD(CustomBoard); \ No newline at end of file diff --git a/main/boards/waveshare-c6-touch-amoled-2.06/README.md b/main/boards/waveshare-c6-touch-amoled-2.06/README.md new file mode 100644 index 0000000..ee4ae2b --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-2.06/README.md @@ -0,0 +1,4 @@ +# Waveshare ESP32-C6-Touch-AMOLED-2.06 + + +[ESP32-C6-Touch-AMOLED-2.06](https://www.waveshare.com/esp32-c6-touch-amoled-2.06.htm) is a high-performance wearable watch-shaped development board launched by Waveshare. This product is based on the ESP32-C6 microcontroller and integrates a 2.06-inch capacitive touch high-definition AMOLED screen, a six-axis sensor, RTC, audio codec chip, and power management, among other functional modules. With a custom case, its appearance is consistent with that of a smartwatch, and it is specifically designed for prototype development and functional verification of wearable applications. \ No newline at end of file diff --git a/main/boards/waveshare-c6-touch-amoled-2.06/config.h b/main/boards/waveshare-c6-touch-amoled-2.06/config.h new file mode 100644 index 0000000..1d884f3 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-2.06/config.h @@ -0,0 +1,46 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE false + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_19 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_22 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_20 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_21 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_23 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_6 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + +#define EXAMPLE_PIN_NUM_LCD_CS GPIO_NUM_5 +#define EXAMPLE_PIN_NUM_LCD_PCLK GPIO_NUM_0 +#define EXAMPLE_PIN_NUM_LCD_DATA0 GPIO_NUM_1 +#define EXAMPLE_PIN_NUM_LCD_DATA1 GPIO_NUM_2 +#define EXAMPLE_PIN_NUM_LCD_DATA2 GPIO_NUM_3 +#define EXAMPLE_PIN_NUM_LCD_DATA3 GPIO_NUM_4 +#define EXAMPLE_PIN_NUM_LCD_RST GPIO_NUM_11 + +#define DISPLAY_WIDTH 410 +#define DISPLAY_HEIGHT 502 + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-c6-touch-amoled-2.06/config.json b/main/boards/waveshare-c6-touch-amoled-2.06/config.json new file mode 100644 index 0000000..3fb9dd9 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-2.06/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-c6-touch-amoled-2.06", + "sdkconfig_append": [ + "CONFIG_USE_ESP_WAKE_WORD=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-c6-touch-amoled-2.06/esp32-c6-touch-amoled-2.06.cc b/main/boards/waveshare-c6-touch-amoled-2.06/esp32-c6-touch-amoled-2.06.cc new file mode 100644 index 0000000..2e2bd71 --- /dev/null +++ b/main/boards/waveshare-c6-touch-amoled-2.06/esp32-c6-touch-amoled-2.06.cc @@ -0,0 +1,314 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" + +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "settings.h" + +#include +#include + +#define TAG "WaveshareEsp32c6TouchAMOLED2inch06" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + WriteReg(0x93, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x03); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x0A); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x03ULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const sh8601_lcd_init_cmd_t vendor_specific_init[] = { + // set display to qspi mode + {0x11, (uint8_t []){0x00}, 0, 120}, + {0xC4, (uint8_t []){0x80}, 1, 0}, + {0x44, (uint8_t []){0x01, 0xD1}, 2, 0}, + {0x35, (uint8_t []){0x00}, 1, 0}, + {0x53, (uint8_t []){0x20}, 1, 10}, + {0x63, (uint8_t []){0xFF}, 1, 10}, + {0x51, (uint8_t []){0x00}, 1, 10}, + {0x2A, (uint8_t []){0x00,0x16,0x01,0xAF}, 4, 0}, + {0x2B, (uint8_t []){0x00,0x00,0x01,0xF5}, 4, 0}, + {0x29, (uint8_t []){0x00}, 0, 10}, + {0x51, (uint8_t []){0xFF}, 1, 0}, +}; + +// 在waveshare_amoled_2_06类之前添加新的显示类 +class CustomLcdDisplay : public SpiLcdDisplay { +public: + static void rounder_event_cb(lv_event_t* e) { + lv_area_t* area = (lv_area_t* )lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + + // round the start of coordinate down to the nearest 2M number + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + // round the end of coordinate up to the nearest 2N+1 number + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES* 0.1, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES* 0.1, 0); + lv_display_add_event_cb(display_, rounder_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(esp_lcd_panel_io_handle_t panel_io) : Backlight(), panel_io_(panel_io) {} + +protected: + esp_lcd_panel_io_handle_t panel_io_; + + virtual void SetBrightnessImpl(uint8_t brightness) override { + auto display = Board::GetInstance().GetDisplay(); + DisplayLockGuard lock(display); + uint8_t data[1] = {((uint8_t)((255* brightness) / 100))}; + int lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_WRITE_CMD << 24; + esp_lcd_panel_io_tx_param(panel_io_, lcd_cmd, &data, sizeof(data)); + } +}; + +class WaveshareEsp32c6TouchAMOLED2inch06 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + CustomLcdDisplay* display_; + CustomBacklight* backlight_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); }); + power_save_timer_->OnShutdownRequest([this](){ + pmic_->PowerOff(); }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.sclk_io_num = EXAMPLE_PIN_NUM_LCD_PCLK; + buscfg.data0_io_num = EXAMPLE_PIN_NUM_LCD_DATA0; + buscfg.data1_io_num = EXAMPLE_PIN_NUM_LCD_DATA1; + buscfg.data2_io_num = EXAMPLE_PIN_NUM_LCD_DATA2; + buscfg.data3_io_num = EXAMPLE_PIN_NUM_LCD_DATA3; + buscfg.max_transfer_sz = DISPLAY_WIDTH* DISPLAY_HEIGHT* sizeof(uint16_t); + buscfg.flags = SPICOMMON_BUSFLAG_QUAD; + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeSH8601Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = SH8601_PANEL_IO_QSPI_CONFIG( + EXAMPLE_PIN_NUM_LCD_CS, + nullptr, + nullptr); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const sh8601_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(sh8601_lcd_init_cmd_t), + .flags = { + .use_qspi_interface = 1, + }}; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = EXAMPLE_PIN_NUM_LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void* )&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(panel_io, &panel_config, &panel)); + esp_lcd_panel_set_gap(panel, 0x16, 0); + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + backlight_ = new CustomBacklight(panel_io); + backlight_->RestoreBrightness(); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + WaveshareEsp32c6TouchAMOLED2inch06() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeAxp2101(); + InitializeSpi(); + InitializeSH8601Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + return backlight_; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) + { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) + { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32c6TouchAMOLED2inch06); diff --git a/main/boards/waveshare-p4-nano/README.md b/main/boards/waveshare-p4-nano/README.md new file mode 100644 index 0000000..580785c --- /dev/null +++ b/main/boards/waveshare-p4-nano/README.md @@ -0,0 +1,43 @@ +# Waveshare ESP32-P4-NANO + + +[ESP32-P4-NANO](https://www.waveshare.com/esp32-p4-nano.htm) is a small size and highly integrated development board designed by waveshare electronics based on ESP32-P4 chip + + + +## Display Page + + +### Recommended display screen + +| Product ID | Dependency | tested | +|----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|------------------------------------------------------------------|--------| +| [10.1-DSI-TOUCH-A](https://www.waveshare.com/10.1-dsi-touch-a.htm)
| [waveshare/esp_lcd_jd9365_10_1](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_jd9365_10_1) | ✅ | +| [101M-8001280-IPS-CT-K](https://www.waveshare.com/101m-8001280-ips-ct-k.htm)
| [waveshare/esp_lcd_jd9365_10_1](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_jd9365_10_1) | ✅ | + +### Common Raspberry adapter screen + +**These displays are supported on [ESP32-P4-NANO BSP](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/bsp/esp32_p4_nano), but not on xiaozhi-esp32** + +
+View full display + +| Product ID | Dependency | tested | +|----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|------------------------------------------------------------------|--------| +| [2.8inch DSI LCD](https://www.waveshare.com/2.8inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [3.4inch DSI LCD (C)](https://www.waveshare.com/3.4inch-dsi-lcd-c.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [4inch DSI LCD (C)](https://www.waveshare.com/4inch-dsi-lcd-c.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [4inch DSI LCD](https://www.waveshare.com/4inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [5inch DSI LCD (D)](https://www.waveshare.com/5inch-dsi-lcd-d.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [6.25inch DSI LCD](https://www.waveshare.com/6.25inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [5inch DSI LCD (C)](https://www.waveshare.com/5inch-dsi-lcd-c.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [7inch DSI LCD (C)](https://www.waveshare.com/7inch-dsi-lcd-c-with-case-a.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [7.9inch DSI LCD](https://www.waveshare.com/7.9inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [7inch DSI LCD (E)](https://www.waveshare.com/7inch-dsi-lcd-e.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [8inch DSI LCD (C)](https://www.waveshare.com/8inch-dsi-lcd-c.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [10.1inch DSI LCD (C)](https://www.waveshare.com/10.1inch-dsi-lcd-c.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [8.8inch DSI LCD](https://www.waveshare.com/8.8inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [11.9inch DSI LCD](https://www.waveshare.com/11.9inch-dsi-lcd.htm)
| [waveshare/esp_lcd_dsi](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_dsi) | 🕒 | +| [7-DSI-TOUCH-A](https://www.waveshare.com/7-dsi-touch-a.htm)
| [waveshare/esp_lcd_ili9881c](https://github.com/waveshareteam/Waveshare-ESP32-components/tree/master/display/lcd/esp_lcd_ili9881c) | 🕒 | + +
\ No newline at end of file diff --git a/main/boards/waveshare-p4-nano/config.h b/main/boards/waveshare-p4-nano/config.h new file mode 100644 index 0000000..8fb9ccc --- /dev/null +++ b/main/boards/waveshare-p4-nano/config.h @@ -0,0 +1,44 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_53 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_7 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define DISPLAY_WIDTH 800 +#define DISPLAY_HEIGHT 1280 + +#define LCD_BIT_PER_PIXEL (16) +#define PIN_NUM_LCD_RST GPIO_NUM_NC + +#define DELAY_TIME_MS (3000) +#define LCD_MIPI_DSI_LANE_NUM (2) // 2 data lanes + +#define MIPI_DSI_PHY_PWR_LDO_CHAN (3) +#define MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV (2500) + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-p4-nano/config.json b/main/boards/waveshare-p4-nano/config.json new file mode 100644 index 0000000..832dee1 --- /dev/null +++ b/main/boards/waveshare-p4-nano/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "waveshare-p4-nano-10.1-a", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y", + "CONFIG_LCD_TYPE_800_1280_10_1_INCH_A=y", + "CONFIG_CAMERA_OV5647=y", + "CONFIG_CAMERA_OV5647_AUTO_DETECT_MIPI_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5647_MIPI_RAW8_800X800_50FPS=y", + "CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-p4-nano/esp32-p4-nano.cc b/main/boards/waveshare-p4-nano/esp32-p4-nano.cc new file mode 100644 index 0000000..9a87981 --- /dev/null +++ b/main/boards/waveshare-p4-nano/esp32-p4-nano.cc @@ -0,0 +1,261 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "display/lcd_display.h" +// #include "display/no_display.h" +#include "button.h" +#include "config.h" + +#include "esp32_camera.h" +#include "esp_video_init.h" +#include "esp_cam_sensor_xclk.h" + +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" + +#include "esp_lcd_mipi_dsi.h" +#include "esp_lcd_jd9365_10_1.h" + +#include +#include +#include +#include +#include "esp_lcd_touch_gt911.h" +#define TAG "WaveshareEsp32p4nano" + +class CustomBacklight : public Backlight { +public: + CustomBacklight(i2c_master_bus_handle_t i2c_handle) + : Backlight(), i2c_handle_(i2c_handle) {} + +protected: + i2c_master_bus_handle_t i2c_handle_; + + virtual void SetBrightnessImpl(uint8_t brightness) override { + uint8_t i2c_address = 0x45; // 7-bit address +#if CONFIG_LCD_TYPE_800_1280_10_1_INCH + uint8_t reg = 0x86; +#elif CONFIG_LCD_TYPE_800_1280_10_1_INCH_A + uint8_t reg = 0x96; +#endif + uint8_t data[2] = {reg, brightness}; + + i2c_master_dev_handle_t dev_handle; + i2c_device_config_t dev_cfg = { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = i2c_address, + .scl_speed_hz = 100000, + }; + + esp_err_t err = i2c_master_bus_add_device(i2c_handle_, &dev_cfg, &dev_handle); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to add I2C device: %s", esp_err_to_name(err)); + return; + } + + err = i2c_master_transmit(dev_handle, data, sizeof(data), -1); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to transmit brightness: %s", esp_err_to_name(err)); + } else { + ESP_LOGI(TAG, "Backlight brightness set to %u", brightness); + } + + // i2c_master_bus_rm_device(dev_handle); + } +}; + +class WaveshareEsp32p4nano : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + LcdDisplay *display__; + Esp32Camera* camera_ = nullptr; + CustomBacklight *backlight_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power(void) { +#if MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + // Turn on the power for MIPI DSI PHY, so it can go from "No Power" state to "Shutdown" state + static esp_ldo_channel_handle_t phy_pwr_chan = NULL; + esp_ldo_channel_config_t ldo_cfg = { + .chan_id = MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + esp_ldo_acquire_channel(&ldo_cfg, &phy_pwr_chan); + ESP_LOGI(TAG, "MIPI DSI PHY Powered on"); +#endif // BSP_MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + + return ESP_OK; + } + + void InitializeLCD() { + bsp_enable_dsi_phy_power(); + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 1500, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_config = JD9365_PANEL_IO_DBI_CONFIG(); + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 80, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 1, + .video_timing = { + .h_size = 800, + .v_size = 1280, + .hsync_pulse_width = 20, + .hsync_back_porch = 20, + .hsync_front_porch = 40, + .vsync_pulse_width = 10, + .vsync_back_porch = 4, + .vsync_front_porch = 30, + }, + .flags = { + .use_dma2d = true, + }, + }; + + jd9365_vendor_config_t vendor_config = { + + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + .lane_num = 2, + }, + .flags = { + .use_mipi_interface = 1, + }, + }; + + const esp_lcd_panel_dev_config_t lcd_dev_config = { + .reset_gpio_num = PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_jd9365(io, &lcd_dev_config, &disp_panel); + esp_lcd_panel_reset(disp_panel); + esp_lcd_panel_init(disp_panel); + + display__ = new MipiLcdDisplay(io, disp_panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + backlight_ = new CustomBacklight(codec_i2c_bus_); + backlight_->RestoreBrightness(); + } + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.scl_speed_hz = 100 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(codec_i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + void InitializeCamera() { + esp_video_init_csi_config_t base_csi_config = { + .sccb_config = { + .init_sccb = false, + .i2c_handle = codec_i2c_bus_, + .freq = 400000, + }, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + }; + + esp_video_init_config_t cam_config = { + .csi = &base_csi_config, + }; + + camera_ = new Esp32Camera(cam_config); + } + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + +public: + WaveshareEsp32p4nano() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeLCD(); + InitializeTouch(); + InitializeCamera(); + InitializeButtons(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_1, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display__; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Backlight *GetBacklight() override { + return backlight_; + } + +}; + +DECLARE_BOARD(WaveshareEsp32p4nano); diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-4b/README.md b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/README.md new file mode 100644 index 0000000..eb94e64 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/README.md @@ -0,0 +1,12 @@ +# Waveshare ESP32-P4-WIFI6-Touch-LCD-4B + + +[ESP32-P4-WIFI6-Touch-LCD-4B](https://www.waveshare.com/esp32-p4-wifi6-touch-lcd-4b.htm) is waveshare electronics designed an intelligent 86 box based on ESP32-P4 module equipped with a 720*720 IPS capacitive touch screen + + +## Configuration + +Configuration in `menuconfig`. + +Selection Board Type `Xiaozhi Assistant --> Board Type` +- Waveshare ESP32-P4-WIFI6-Touch-LCD-4B \ No newline at end of file diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.h b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.h new file mode 100644 index 0000000..027c215 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_53 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_7 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define DISPLAY_WIDTH 720 +#define DISPLAY_HEIGHT 720 + +#define LCD_BIT_PER_PIXEL (16) +#define PIN_NUM_LCD_RST GPIO_NUM_27 + +#define DELAY_TIME_MS (3000) +#define LCD_MIPI_DSI_LANE_NUM (2) // 2 data lanes + +#define MIPI_DSI_PHY_PWR_LDO_CHAN (3) +#define MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV (2500) + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_26 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.json b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.json new file mode 100644 index 0000000..5a8dbb5 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "waveshare-p4-wifi6-touch-lcd-4b", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_CAMERA_OV5647=y", + "CONFIG_CAMERA_OV5647_AUTO_DETECT_MIPI_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5647_MIPI_RAW8_800X800_50FPS=y", + "CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-4b/esp32-p4-wifi6-touch-lcd-4b.cc b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/esp32-p4-wifi6-touch-lcd-4b.cc new file mode 100644 index 0000000..68a2947 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-4b/esp32-p4-wifi6-touch-lcd-4b.cc @@ -0,0 +1,226 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "display/lcd_display.h" +// #include "display/no_display.h" +#include "button.h" +#include "config.h" + +#include "esp32_camera.h" +#include "esp_video_init.h" +#include "esp_cam_sensor_xclk.h" + +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" + +#include "esp_lcd_st7703.h" + +#include +#include +#include +#include +#include "esp_lcd_touch_gt911.h" +#define TAG "WaveshareEsp32p44b" + +class WaveshareEsp32p44b : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay *display_; + Esp32Camera* camera_ = nullptr; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power(void) { +#if MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + // Turn on the power for MIPI DSI PHY, so it can go from "No Power" state to "Shutdown" state + static esp_ldo_channel_handle_t phy_pwr_chan = NULL; + esp_ldo_channel_config_t ldo_cfg = { + .chan_id = MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + esp_ldo_acquire_channel(&ldo_cfg, &phy_pwr_chan); + ESP_LOGI(TAG, "MIPI DSI PHY Powered on"); +#endif // BSP_MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + + return ESP_OK; + } + + void InitializeLCD() { + bsp_enable_dsi_phy_power(); + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 480, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_config = ST7703_PANEL_IO_DBI_CONFIG(); + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 46, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 1, + .video_timing = { + .h_size = 720, + .v_size = 720, + .hsync_pulse_width = 20, + .hsync_back_porch = 80, + .hsync_front_porch = 80, + .vsync_pulse_width = 4, + .vsync_back_porch = 12, + .vsync_front_porch = 30, + }, + .flags = { + .use_dma2d = true, + }, + }; + st7703_vendor_config_t vendor_config = { + + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + }, + .flags = { + .use_mipi_interface = 1, + }, + }; + + const esp_lcd_panel_dev_config_t lcd_dev_config = { + .reset_gpio_num = PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_st7703(io, &lcd_dev_config, &disp_panel); + esp_lcd_panel_reset(disp_panel); + esp_lcd_panel_init(disp_panel); + + display_ = new MipiLcdDisplay(io, disp_panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_23, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + void InitializeCamera() { + esp_video_init_csi_config_t base_csi_config = { + .sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 400000, + }, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + }; + + esp_video_init_config_t cam_config = { + .csi = &base_csi_config, + }; + + camera_ = new Esp32Camera(cam_config); + } + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + +public: + WaveshareEsp32p44b() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeLCD(); + InitializeTouch(); + InitializeCamera(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + +}; + +DECLARE_BOARD(WaveshareEsp32p44b); diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-7b/README.md b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/README.md new file mode 100644 index 0000000..9f45fa6 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/README.md @@ -0,0 +1,12 @@ +# Waveshare ESP32-P4-WIFI6-Touch-LCD-7B + + +[ESP32-P4-WIFI6-Touch-LCD-7B](https://www.waveshare.com/esp32-p4-wifi6-touch-lcd-7b.htm) is waveshare electronics designed an intelligent 86 box based on ESP32-P4 module equipped with a 1024*600 IPS capacitive touch screen + + +## Configuration + +Configuration in `menuconfig`. + +Selection Board Type `Xiaozhi Assistant --> Board Type` +- Waveshare ESP32-P4-WIFI6-Touch-LCD-7B \ No newline at end of file diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.h b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.h new file mode 100644 index 0000000..2f7d08c --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_53 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_7 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define DISPLAY_WIDTH 1024 +#define DISPLAY_HEIGHT 600 + +#define LCD_BIT_PER_PIXEL (16) +#define PIN_NUM_LCD_RST GPIO_NUM_33 + +#define DELAY_TIME_MS (3000) +#define LCD_MIPI_DSI_LANE_NUM (2) // 2 data lanes + +#define MIPI_DSI_PHY_PWR_LDO_CHAN (3) +#define MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV (2500) + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_32 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.json b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.json new file mode 100644 index 0000000..8f84bf9 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "waveshare-p4-wifi6-touch-lcd-7b", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_CAMERA_OV5647=y", + "CONFIG_CAMERA_OV5647_AUTO_DETECT_MIPI_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5647_MIPI_RAW8_800X800_50FPS=y", + "CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-7b/esp32-p4-wifi6-touch-lcd-7b.cc b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/esp32-p4-wifi6-touch-lcd-7b.cc new file mode 100644 index 0000000..ebc12fc --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-7b/esp32-p4-wifi6-touch-lcd-7b.cc @@ -0,0 +1,247 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "display/lcd_display.h" +// #include "display/no_display.h" +#include "button.h" +#include "config.h" + +#include "esp32_camera.h" +#include "esp_video_init.h" +#include "esp_cam_sensor_xclk.h" + +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" + +#include "esp_lcd_ek79007.h" + +#include +#include +#include +#include +#include "esp_lcd_touch_gt911.h" +#define TAG "WaveshareEsp32p47b" + +class WaveshareEsp32p47b : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay *display_; + Esp32Camera* camera_ = nullptr; + + esp_err_t i2c_device_probe(uint8_t addr) { + return i2c_master_probe(i2c_bus_, addr, 100); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power(void) { +#if MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + // Turn on the power for MIPI DSI PHY, so it can go from "No Power" state to "Shutdown" state + static esp_ldo_channel_handle_t phy_pwr_chan = NULL; + esp_ldo_channel_config_t ldo_cfg = { + .chan_id = MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + esp_ldo_acquire_channel(&ldo_cfg, &phy_pwr_chan); + ESP_LOGI(TAG, "MIPI DSI PHY Powered on"); +#endif // BSP_MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + + return ESP_OK; + } + + void InitializeLCD() { + bsp_enable_dsi_phy_power(); + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 900, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_config = EK79007_PANEL_IO_DBI_CONFIG(); + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 52, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 1, + .video_timing = { + .h_size = 1024, + .v_size = 600, + .hsync_pulse_width = 10, + .hsync_back_porch = 160, + .hsync_front_porch = 160, + .vsync_pulse_width = 1, + .vsync_back_porch = 23, + .vsync_front_porch = 12, + }, + .flags = { + .use_dma2d = true, + }, + }; + ek79007_vendor_config_t vendor_config = { + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + }, + }; + + const esp_lcd_panel_dev_config_t lcd_dev_config = { + .reset_gpio_num = PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_ek79007(io, &lcd_dev_config, &disp_panel); + esp_lcd_panel_reset(disp_panel); + esp_lcd_panel_init(disp_panel); + + display_ = new MipiLcdDisplay(io, disp_panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + + lv_display_t *disp = lv_display_get_default(); + if (disp) { + lv_disp_set_rotation(disp, LV_DISPLAY_ROTATION_180); + ESP_LOGI(TAG, "Display rotated 180 degrees"); + } else { + ESP_LOGE(TAG, "Failed to get default display for rotation"); + } + } + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_23, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + if (ESP_OK == i2c_device_probe(ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS)) { + ESP_LOGI(TAG, "Touch panel found at address 0x%02X", ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS); + } else if (ESP_OK == i2c_device_probe(ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS_BACKUP)) { + ESP_LOGI(TAG, "Touch panel found at address 0x%02X", ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS_BACKUP); + tp_io_config.dev_addr = ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS_BACKUP; + } else { + ESP_LOGE(TAG, "Touch panel not found on I2C bus"); + ESP_LOGE(TAG, "Tried addresses: 0x%02X and 0x%02X", + ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS, + ESP_LCD_TOUCH_IO_I2C_GT911_ADDRESS_BACKUP); + return; + } + + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + void InitializeCamera() { + esp_video_init_csi_config_t base_csi_config = { + .sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 400000, + }, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + }; + + esp_video_init_config_t cam_config = { + .csi = &base_csi_config, + }; + + camera_ = new Esp32Camera(cam_config); + } + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + +public: + WaveshareEsp32p47b() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeLCD(); + InitializeTouch(); + InitializeCamera(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + +}; + +DECLARE_BOARD(WaveshareEsp32p47b); diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-xc/README.md b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/README.md new file mode 100644 index 0000000..09271dd --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/README.md @@ -0,0 +1,22 @@ +# Waveshare ESP32-P4-WIFI6-Touch-LCD-XC + + +[ESP32-P4-WIFI6-Touch-LCD-XC](https://www.waveshare.com/esp32-p4-wifi6-touch-lcd-3.4c.htm) is waveshare electronics designed a 3.4-inch, 4-inch circular screen, highly integrated development board + + +## Configuration + +Configuration in `menuconfig`. + +Selection Board Type `Xiaozhi Assistant --> Board Type` +- Waveshare ESP32-P4-WIFI6-Touch-LCD-3.4C or ESP32-P4-WIFI6-Touch-LCD-4C + +Selection Display LCD Type `Xiaozhi Assistant --> LCD Type` +- Waveshare ESP32-P4-WIFI6-Touch-LCD-3.4C with 800*800 3.4inch round display +- Waveshare ESP32-P4-WIFI6-Touch-LCD-4C with 720*720 4inch round display + + + +| [ESP32-P4-WIFI6-Touch-LCD-3.4C](https://www.waveshare.com/esp32-p4-wifi6-touch-lcd-3.4c.htm) | [ESP32-P4-WIFI6-Touch-LCD-4C](https://www.waveshare.com/esp32-p4-wifi6-touch-lcd-4c.htm) | +|----------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------| +| | | diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.h b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.h new file mode 100644 index 0000000..30e73ae --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.h @@ -0,0 +1,490 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_53 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_7 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define LCD_BIT_PER_PIXEL (16) +#define PIN_NUM_LCD_RST GPIO_NUM_27 + +#define DELAY_TIME_MS (3000) +#define LCD_MIPI_DSI_LANE_NUM (2) // 2 data lanes + +#define MIPI_DSI_PHY_PWR_LDO_CHAN (3) +#define MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV (2500) + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_26 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#if CONFIG_LCD_TYPE_800_800_3_4_INCH +#define DISPLAY_WIDTH 800 +#define DISPLAY_HEIGHT 800 + +static const jd9365_lcd_init_cmd_t lcd_init_cmds[] = { + {0xE0, (uint8_t[]){0x00}, 1, 0}, + + {0xE1, (uint8_t[]){0x93}, 1, 0}, + {0xE2, (uint8_t[]){0x65}, 1, 0}, + {0xE3, (uint8_t[]){0xF8}, 1, 0}, + {0x80, (uint8_t[]){0x01}, 1, 0}, + + {0xE0, (uint8_t[]){0x01}, 1, 0}, + + {0x00, (uint8_t[]){0x00}, 1, 0}, + {0x01, (uint8_t[]){0x41}, 1, 0}, + {0x03, (uint8_t[]){0x10}, 1, 0}, + {0x04, (uint8_t[]){0x44}, 1, 0}, + + {0x17, (uint8_t[]){0x00}, 1, 0}, + {0x18, (uint8_t[]){0xD0}, 1, 0}, + {0x19, (uint8_t[]){0x00}, 1, 0}, + {0x1A, (uint8_t[]){0x00}, 1, 0}, + {0x1B, (uint8_t[]){0xD0}, 1, 0}, + {0x1C, (uint8_t[]){0x00}, 1, 0}, + + {0x24, (uint8_t[]){0xFE}, 1, 0}, + {0x35, (uint8_t[]){0x26}, 1, 0}, + + {0x37, (uint8_t[]){0x09}, 1, 0}, + + {0x38, (uint8_t[]){0x04}, 1, 0}, + {0x39, (uint8_t[]){0x08}, 1, 0}, + {0x3A, (uint8_t[]){0x0A}, 1, 0}, + {0x3C, (uint8_t[]){0x78}, 1, 0}, + {0x3D, (uint8_t[]){0xFF}, 1, 0}, + {0x3E, (uint8_t[]){0xFF}, 1, 0}, + {0x3F, (uint8_t[]){0xFF}, 1, 0}, + + {0x40, (uint8_t[]){0x00}, 1, 0}, + {0x41, (uint8_t[]){0x64}, 1, 0}, + {0x42, (uint8_t[]){0xC7}, 1, 0}, + {0x43, (uint8_t[]){0x18}, 1, 0}, + {0x44, (uint8_t[]){0x0B}, 1, 0}, + {0x45, (uint8_t[]){0x14}, 1, 0}, + + {0x55, (uint8_t[]){0x02}, 1, 0}, + {0x57, (uint8_t[]){0x49}, 1, 0}, + {0x59, (uint8_t[]){0x0A}, 1, 0}, + {0x5A, (uint8_t[]){0x1B}, 1, 0}, + {0x5B, (uint8_t[]){0x19}, 1, 0}, + + {0x5D, (uint8_t[]){0x7F}, 1, 0}, + {0x5E, (uint8_t[]){0x56}, 1, 0}, + {0x5F, (uint8_t[]){0x43}, 1, 0}, + {0x60, (uint8_t[]){0x37}, 1, 0}, + {0x61, (uint8_t[]){0x33}, 1, 0}, + {0x62, (uint8_t[]){0x25}, 1, 0}, + {0x63, (uint8_t[]){0x2A}, 1, 0}, + {0x64, (uint8_t[]){0x16}, 1, 0}, + {0x65, (uint8_t[]){0x30}, 1, 0}, + {0x66, (uint8_t[]){0x2F}, 1, 0}, + {0x67, (uint8_t[]){0x32}, 1, 0}, + {0x68, (uint8_t[]){0x53}, 1, 0}, + {0x69, (uint8_t[]){0x43}, 1, 0}, + {0x6A, (uint8_t[]){0x4C}, 1, 0}, + {0x6B, (uint8_t[]){0x40}, 1, 0}, + {0x6C, (uint8_t[]){0x3D}, 1, 0}, + {0x6D, (uint8_t[]){0x31}, 1, 0}, + {0x6E, (uint8_t[]){0x20}, 1, 0}, + {0x6F, (uint8_t[]){0x0F}, 1, 0}, + + {0x70, (uint8_t[]){0x7F}, 1, 0}, + {0x71, (uint8_t[]){0x56}, 1, 0}, + {0x72, (uint8_t[]){0x43}, 1, 0}, + {0x73, (uint8_t[]){0x37}, 1, 0}, + {0x74, (uint8_t[]){0x33}, 1, 0}, + {0x75, (uint8_t[]){0x25}, 1, 0}, + {0x76, (uint8_t[]){0x2A}, 1, 0}, + {0x77, (uint8_t[]){0x16}, 1, 0}, + {0x78, (uint8_t[]){0x30}, 1, 0}, + {0x79, (uint8_t[]){0x2F}, 1, 0}, + {0x7A, (uint8_t[]){0x32}, 1, 0}, + {0x7B, (uint8_t[]){0x53}, 1, 0}, + {0x7C, (uint8_t[]){0x43}, 1, 0}, + {0x7D, (uint8_t[]){0x4C}, 1, 0}, + {0x7E, (uint8_t[]){0x40}, 1, 0}, + {0x7F, (uint8_t[]){0x3D}, 1, 0}, + {0x80, (uint8_t[]){0x31}, 1, 0}, + {0x81, (uint8_t[]){0x20}, 1, 0}, + {0x82, (uint8_t[]){0x0F}, 1, 0}, + + {0xE0, (uint8_t[]){0x02}, 1, 0}, + {0x00, (uint8_t[]){0x5F}, 1, 0}, + {0x01, (uint8_t[]){0x5F}, 1, 0}, + {0x02, (uint8_t[]){0x5E}, 1, 0}, + {0x03, (uint8_t[]){0x5E}, 1, 0}, + {0x04, (uint8_t[]){0x50}, 1, 0}, + {0x05, (uint8_t[]){0x48}, 1, 0}, + {0x06, (uint8_t[]){0x48}, 1, 0}, + {0x07, (uint8_t[]){0x4A}, 1, 0}, + {0x08, (uint8_t[]){0x4A}, 1, 0}, + {0x09, (uint8_t[]){0x44}, 1, 0}, + {0x0A, (uint8_t[]){0x44}, 1, 0}, + {0x0B, (uint8_t[]){0x46}, 1, 0}, + {0x0C, (uint8_t[]){0x46}, 1, 0}, + {0x0D, (uint8_t[]){0x5F}, 1, 0}, + {0x0E, (uint8_t[]){0x5F}, 1, 0}, + {0x0F, (uint8_t[]){0x57}, 1, 0}, + {0x10, (uint8_t[]){0x57}, 1, 0}, + {0x11, (uint8_t[]){0x77}, 1, 0}, + {0x12, (uint8_t[]){0x77}, 1, 0}, + {0x13, (uint8_t[]){0x40}, 1, 0}, + {0x14, (uint8_t[]){0x42}, 1, 0}, + {0x15, (uint8_t[]){0x5F}, 1, 0}, + + {0x16, (uint8_t[]){0x5F}, 1, 0}, + {0x17, (uint8_t[]){0x5F}, 1, 0}, + {0x18, (uint8_t[]){0x5E}, 1, 0}, + {0x19, (uint8_t[]){0x5E}, 1, 0}, + {0x1A, (uint8_t[]){0x50}, 1, 0}, + {0x1B, (uint8_t[]){0x49}, 1, 0}, + {0x1C, (uint8_t[]){0x49}, 1, 0}, + {0x1D, (uint8_t[]){0x4B}, 1, 0}, + {0x1E, (uint8_t[]){0x4B}, 1, 0}, + {0x1F, (uint8_t[]){0x45}, 1, 0}, + {0x20, (uint8_t[]){0x45}, 1, 0}, + {0x21, (uint8_t[]){0x47}, 1, 0}, + {0x22, (uint8_t[]){0x47}, 1, 0}, + {0x23, (uint8_t[]){0x5F}, 1, 0}, + {0x24, (uint8_t[]){0x5F}, 1, 0}, + {0x25, (uint8_t[]){0x57}, 1, 0}, + {0x26, (uint8_t[]){0x57}, 1, 0}, + {0x27, (uint8_t[]){0x77}, 1, 0}, + {0x28, (uint8_t[]){0x77}, 1, 0}, + {0x29, (uint8_t[]){0x41}, 1, 0}, + {0x2A, (uint8_t[]){0x43}, 1, 0}, + {0x2B, (uint8_t[]){0x5F}, 1, 0}, + + {0x2C, (uint8_t[]){0x1E}, 1, 0}, + {0x2D, (uint8_t[]){0x1E}, 1, 0}, + {0x2E, (uint8_t[]){0x1F}, 1, 0}, + {0x2F, (uint8_t[]){0x1F}, 1, 0}, + {0x30, (uint8_t[]){0x10}, 1, 0}, + {0x31, (uint8_t[]){0x07}, 1, 0}, + {0x32, (uint8_t[]){0x07}, 1, 0}, + {0x33, (uint8_t[]){0x05}, 1, 0}, + {0x34, (uint8_t[]){0x05}, 1, 0}, + {0x35, (uint8_t[]){0x0B}, 1, 0}, + {0x36, (uint8_t[]){0x0B}, 1, 0}, + {0x37, (uint8_t[]){0x09}, 1, 0}, + {0x38, (uint8_t[]){0x09}, 1, 0}, + {0x39, (uint8_t[]){0x1F}, 1, 0}, + {0x3A, (uint8_t[]){0x1F}, 1, 0}, + {0x3B, (uint8_t[]){0x17}, 1, 0}, + {0x3C, (uint8_t[]){0x17}, 1, 0}, + {0x3D, (uint8_t[]){0x17}, 1, 0}, + {0x3E, (uint8_t[]){0x17}, 1, 0}, + {0x3F, (uint8_t[]){0x03}, 1, 0}, + {0x40, (uint8_t[]){0x01}, 1, 0}, + {0x41, (uint8_t[]){0x1F}, 1, 0}, + + {0x42, (uint8_t[]){0x1E}, 1, 0}, + {0x43, (uint8_t[]){0x1E}, 1, 0}, + {0x44, (uint8_t[]){0x1F}, 1, 0}, + {0x45, (uint8_t[]){0x1F}, 1, 0}, + {0x46, (uint8_t[]){0x10}, 1, 0}, + {0x47, (uint8_t[]){0x06}, 1, 0}, + {0x48, (uint8_t[]){0x06}, 1, 0}, + {0x49, (uint8_t[]){0x04}, 1, 0}, + {0x4A, (uint8_t[]){0x04}, 1, 0}, + {0x4B, (uint8_t[]){0x0A}, 1, 0}, + {0x4C, (uint8_t[]){0x0A}, 1, 0}, + {0x4D, (uint8_t[]){0x08}, 1, 0}, + {0x4E, (uint8_t[]){0x08}, 1, 0}, + {0x4F, (uint8_t[]){0x1F}, 1, 0}, + {0x50, (uint8_t[]){0x1F}, 1, 0}, + {0x51, (uint8_t[]){0x17}, 1, 0}, + {0x52, (uint8_t[]){0x17}, 1, 0}, + {0x53, (uint8_t[]){0x17}, 1, 0}, + {0x54, (uint8_t[]){0x17}, 1, 0}, + {0x55, (uint8_t[]){0x02}, 1, 0}, + {0x56, (uint8_t[]){0x00}, 1, 0}, + {0x57, (uint8_t[]){0x1F}, 1, 0}, + + {0xE0, (uint8_t[]){0x02}, 1, 0}, + {0x58, (uint8_t[]){0x40}, 1, 0}, + {0x59, (uint8_t[]){0x00}, 1, 0}, + {0x5A, (uint8_t[]){0x00}, 1, 0}, + {0x5B, (uint8_t[]){0x30}, 1, 0}, + {0x5C, (uint8_t[]){0x01}, 1, 0}, + {0x5D, (uint8_t[]){0x30}, 1, 0}, + {0x5E, (uint8_t[]){0x01}, 1, 0}, + {0x5F, (uint8_t[]){0x02}, 1, 0}, + {0x60, (uint8_t[]){0x30}, 1, 0}, + {0x61, (uint8_t[]){0x03}, 1, 0}, + {0x62, (uint8_t[]){0x04}, 1, 0}, + {0x63, (uint8_t[]){0x04}, 1, 0}, + {0x64, (uint8_t[]){0xA6}, 1, 0}, + {0x65, (uint8_t[]){0x43}, 1, 0}, + {0x66, (uint8_t[]){0x30}, 1, 0}, + {0x67, (uint8_t[]){0x73}, 1, 0}, + {0x68, (uint8_t[]){0x05}, 1, 0}, + {0x69, (uint8_t[]){0x04}, 1, 0}, + {0x6A, (uint8_t[]){0x7F}, 1, 0}, + {0x6B, (uint8_t[]){0x08}, 1, 0}, + {0x6C, (uint8_t[]){0x00}, 1, 0}, + {0x6D, (uint8_t[]){0x04}, 1, 0}, + {0x6E, (uint8_t[]){0x04}, 1, 0}, + {0x6F, (uint8_t[]){0x88}, 1, 0}, + + {0x75, (uint8_t[]){0xD9}, 1, 0}, + {0x76, (uint8_t[]){0x00}, 1, 0}, + {0x77, (uint8_t[]){0x33}, 1, 0}, + {0x78, (uint8_t[]){0x43}, 1, 0}, + + {0xE0, (uint8_t[]){0x00}, 1, 0}, + + {0x11, (uint8_t[]){0x00}, 1, 120}, + + {0x29, (uint8_t[]){0x00}, 1, 20}, + {0x35, (uint8_t[]){0x00}, 1, 0}, +}; +#else +#define DISPLAY_WIDTH 720 +#define DISPLAY_HEIGHT 720 +static const jd9365_lcd_init_cmd_t lcd_init_cmds[] = { + {0xE0, (uint8_t[]){0x00}, 1, 0}, + + {0xE1, (uint8_t[]){0x93}, 1, 0}, + {0xE2, (uint8_t[]){0x65}, 1, 0}, + {0xE3, (uint8_t[]){0xF8}, 1, 0}, + {0x80, (uint8_t[]){0x01}, 1, 0}, + + {0xE0, (uint8_t[]){0x01}, 1, 0}, + + {0x00, (uint8_t[]){0x00}, 1, 0}, + {0x01, (uint8_t[]){0x41}, 1, 0}, + {0x03, (uint8_t[]){0x10}, 1, 0}, + {0x04, (uint8_t[]){0x44}, 1, 0}, + + {0x17, (uint8_t[]){0x00}, 1, 0}, + {0x18, (uint8_t[]){0xD0}, 1, 0}, + {0x19, (uint8_t[]){0x00}, 1, 0}, + {0x1A, (uint8_t[]){0x00}, 1, 0}, + {0x1B, (uint8_t[]){0xD0}, 1, 0}, + {0x1C, (uint8_t[]){0x00}, 1, 0}, + + {0x24, (uint8_t[]){0xFE}, 1, 0}, + {0x35, (uint8_t[]){0x26}, 1, 0}, + + {0x37, (uint8_t[]){0x09}, 1, 0}, + + {0x38, (uint8_t[]){0x04}, 1, 0}, + {0x39, (uint8_t[]){0x08}, 1, 0}, + {0x3A, (uint8_t[]){0x0A}, 1, 0}, + {0x3C, (uint8_t[]){0x78}, 1, 0}, + {0x3D, (uint8_t[]){0xFF}, 1, 0}, + {0x3E, (uint8_t[]){0xFF}, 1, 0}, + {0x3F, (uint8_t[]){0xFF}, 1, 0}, + + {0x40, (uint8_t[]){0x04}, 1, 0}, + {0x41, (uint8_t[]){0x64}, 1, 0}, + {0x42, (uint8_t[]){0xC7}, 1, 0}, + {0x43, (uint8_t[]){0x18}, 1, 0}, + {0x44, (uint8_t[]){0x0B}, 1, 0}, + {0x45, (uint8_t[]){0x14}, 1, 0}, + + {0x55, (uint8_t[]){0x02}, 1, 0}, + {0x57, (uint8_t[]){0x49}, 1, 0}, + {0x59, (uint8_t[]){0x0A}, 1, 0}, + {0x5A, (uint8_t[]){0x1B}, 1, 0}, + {0x5B, (uint8_t[]){0x19}, 1, 0}, + + {0x5D, (uint8_t[]){0x7F}, 1, 0}, + {0x5E, (uint8_t[]){0x56}, 1, 0}, + {0x5F, (uint8_t[]){0x43}, 1, 0}, + {0x60, (uint8_t[]){0x37}, 1, 0}, + {0x61, (uint8_t[]){0x33}, 1, 0}, + {0x62, (uint8_t[]){0x25}, 1, 0}, + {0x63, (uint8_t[]){0x2A}, 1, 0}, + {0x64, (uint8_t[]){0x16}, 1, 0}, + {0x65, (uint8_t[]){0x30}, 1, 0}, + {0x66, (uint8_t[]){0x2F}, 1, 0}, + {0x67, (uint8_t[]){0x32}, 1, 0}, + {0x68, (uint8_t[]){0x53}, 1, 0}, + {0x69, (uint8_t[]){0x43}, 1, 0}, + {0x6A, (uint8_t[]){0x4C}, 1, 0}, + {0x6B, (uint8_t[]){0x40}, 1, 0}, + {0x6C, (uint8_t[]){0x3D}, 1, 0}, + {0x6D, (uint8_t[]){0x31}, 1, 0}, + {0x6E, (uint8_t[]){0x20}, 1, 0}, + {0x6F, (uint8_t[]){0x0F}, 1, 0}, + + {0x70, (uint8_t[]){0x7F}, 1, 0}, + {0x71, (uint8_t[]){0x56}, 1, 0}, + {0x72, (uint8_t[]){0x43}, 1, 0}, + {0x73, (uint8_t[]){0x37}, 1, 0}, + {0x74, (uint8_t[]){0x33}, 1, 0}, + {0x75, (uint8_t[]){0x25}, 1, 0}, + {0x76, (uint8_t[]){0x2A}, 1, 0}, + {0x77, (uint8_t[]){0x16}, 1, 0}, + {0x78, (uint8_t[]){0x30}, 1, 0}, + {0x79, (uint8_t[]){0x2F}, 1, 0}, + {0x7A, (uint8_t[]){0x32}, 1, 0}, + {0x7B, (uint8_t[]){0x53}, 1, 0}, + {0x7C, (uint8_t[]){0x43}, 1, 0}, + {0x7D, (uint8_t[]){0x4C}, 1, 0}, + {0x7E, (uint8_t[]){0x40}, 1, 0}, + {0x7F, (uint8_t[]){0x3D}, 1, 0}, + {0x80, (uint8_t[]){0x31}, 1, 0}, + {0x81, (uint8_t[]){0x20}, 1, 0}, + {0x82, (uint8_t[]){0x0F}, 1, 0}, + + {0xE0, (uint8_t[]){0x02}, 1, 0}, + {0x00, (uint8_t[]){0x5F}, 1, 0}, + {0x01, (uint8_t[]){0x5F}, 1, 0}, + {0x02, (uint8_t[]){0x5E}, 1, 0}, + {0x03, (uint8_t[]){0x5E}, 1, 0}, + {0x04, (uint8_t[]){0x50}, 1, 0}, + {0x05, (uint8_t[]){0x48}, 1, 0}, + {0x06, (uint8_t[]){0x48}, 1, 0}, + {0x07, (uint8_t[]){0x4A}, 1, 0}, + {0x08, (uint8_t[]){0x4A}, 1, 0}, + {0x09, (uint8_t[]){0x44}, 1, 0}, + {0x0A, (uint8_t[]){0x44}, 1, 0}, + {0x0B, (uint8_t[]){0x46}, 1, 0}, + {0x0C, (uint8_t[]){0x46}, 1, 0}, + {0x0D, (uint8_t[]){0x5F}, 1, 0}, + {0x0E, (uint8_t[]){0x5F}, 1, 0}, + {0x0F, (uint8_t[]){0x57}, 1, 0}, + {0x10, (uint8_t[]){0x57}, 1, 0}, + {0x11, (uint8_t[]){0x77}, 1, 0}, + {0x12, (uint8_t[]){0x77}, 1, 0}, + {0x13, (uint8_t[]){0x40}, 1, 0}, + {0x14, (uint8_t[]){0x42}, 1, 0}, + {0x15, (uint8_t[]){0x5F}, 1, 0}, + + {0x16, (uint8_t[]){0x5F}, 1, 0}, + {0x17, (uint8_t[]){0x5F}, 1, 0}, + {0x18, (uint8_t[]){0x5E}, 1, 0}, + {0x19, (uint8_t[]){0x5E}, 1, 0}, + {0x1A, (uint8_t[]){0x50}, 1, 0}, + {0x1B, (uint8_t[]){0x49}, 1, 0}, + {0x1C, (uint8_t[]){0x49}, 1, 0}, + {0x1D, (uint8_t[]){0x4B}, 1, 0}, + {0x1E, (uint8_t[]){0x4B}, 1, 0}, + {0x1F, (uint8_t[]){0x45}, 1, 0}, + {0x20, (uint8_t[]){0x45}, 1, 0}, + {0x21, (uint8_t[]){0x47}, 1, 0}, + {0x22, (uint8_t[]){0x47}, 1, 0}, + {0x23, (uint8_t[]){0x5F}, 1, 0}, + {0x24, (uint8_t[]){0x5F}, 1, 0}, + {0x25, (uint8_t[]){0x57}, 1, 0}, + {0x26, (uint8_t[]){0x57}, 1, 0}, + {0x27, (uint8_t[]){0x77}, 1, 0}, + {0x28, (uint8_t[]){0x77}, 1, 0}, + {0x29, (uint8_t[]){0x41}, 1, 0}, + {0x2A, (uint8_t[]){0x43}, 1, 0}, + {0x2B, (uint8_t[]){0x5F}, 1, 0}, + + {0x2C, (uint8_t[]){0x1E}, 1, 0}, + {0x2D, (uint8_t[]){0x1E}, 1, 0}, + {0x2E, (uint8_t[]){0x1F}, 1, 0}, + {0x2F, (uint8_t[]){0x1F}, 1, 0}, + {0x30, (uint8_t[]){0x10}, 1, 0}, + {0x31, (uint8_t[]){0x07}, 1, 0}, + {0x32, (uint8_t[]){0x07}, 1, 0}, + {0x33, (uint8_t[]){0x05}, 1, 0}, + {0x34, (uint8_t[]){0x05}, 1, 0}, + {0x35, (uint8_t[]){0x0B}, 1, 0}, + {0x36, (uint8_t[]){0x0B}, 1, 0}, + {0x37, (uint8_t[]){0x09}, 1, 0}, + {0x38, (uint8_t[]){0x09}, 1, 0}, + {0x39, (uint8_t[]){0x1F}, 1, 0}, + {0x3A, (uint8_t[]){0x1F}, 1, 0}, + {0x3B, (uint8_t[]){0x17}, 1, 0}, + {0x3C, (uint8_t[]){0x17}, 1, 0}, + {0x3D, (uint8_t[]){0x17}, 1, 0}, + {0x3E, (uint8_t[]){0x17}, 1, 0}, + {0x3F, (uint8_t[]){0x03}, 1, 0}, + {0x40, (uint8_t[]){0x01}, 1, 0}, + {0x41, (uint8_t[]){0x1F}, 1, 0}, + + {0x42, (uint8_t[]){0x1E}, 1, 0}, + {0x43, (uint8_t[]){0x1E}, 1, 0}, + {0x44, (uint8_t[]){0x1F}, 1, 0}, + {0x45, (uint8_t[]){0x1F}, 1, 0}, + {0x46, (uint8_t[]){0x10}, 1, 0}, + {0x47, (uint8_t[]){0x06}, 1, 0}, + {0x48, (uint8_t[]){0x06}, 1, 0}, + {0x49, (uint8_t[]){0x04}, 1, 0}, + {0x4A, (uint8_t[]){0x04}, 1, 0}, + {0x4B, (uint8_t[]){0x0A}, 1, 0}, + {0x4C, (uint8_t[]){0x0A}, 1, 0}, + {0x4D, (uint8_t[]){0x08}, 1, 0}, + {0x4E, (uint8_t[]){0x08}, 1, 0}, + {0x4F, (uint8_t[]){0x1F}, 1, 0}, + {0x50, (uint8_t[]){0x1F}, 1, 0}, + {0x51, (uint8_t[]){0x17}, 1, 0}, + {0x52, (uint8_t[]){0x17}, 1, 0}, + {0x53, (uint8_t[]){0x17}, 1, 0}, + {0x54, (uint8_t[]){0x17}, 1, 0}, + {0x55, (uint8_t[]){0x02}, 1, 0}, + {0x56, (uint8_t[]){0x00}, 1, 0}, + {0x57, (uint8_t[]){0x1F}, 1, 0}, + + {0xE0, (uint8_t[]){0x02}, 1, 0}, + {0x58, (uint8_t[]){0x40}, 1, 0}, + {0x59, (uint8_t[]){0x00}, 1, 0}, + {0x5A, (uint8_t[]){0x00}, 1, 0}, + {0x5B, (uint8_t[]){0x30}, 1, 0}, + {0x5C, (uint8_t[]){0x01}, 1, 0}, + {0x5D, (uint8_t[]){0x30}, 1, 0}, + {0x5E, (uint8_t[]){0x01}, 1, 0}, + {0x5F, (uint8_t[]){0x02}, 1, 0}, + {0x60, (uint8_t[]){0x30}, 1, 0}, + {0x61, (uint8_t[]){0x03}, 1, 0}, + {0x62, (uint8_t[]){0x04}, 1, 0}, + {0x63, (uint8_t[]){0x04}, 1, 0}, + {0x64, (uint8_t[]){0xA6}, 1, 0}, + {0x65, (uint8_t[]){0x43}, 1, 0}, + {0x66, (uint8_t[]){0x30}, 1, 0}, + {0x67, (uint8_t[]){0x73}, 1, 0}, + {0x68, (uint8_t[]){0x05}, 1, 0}, + {0x69, (uint8_t[]){0x04}, 1, 0}, + {0x6A, (uint8_t[]){0x7F}, 1, 0}, + {0x6B, (uint8_t[]){0x08}, 1, 0}, + {0x6C, (uint8_t[]){0x00}, 1, 0}, + {0x6D, (uint8_t[]){0x04}, 1, 0}, + {0x6E, (uint8_t[]){0x04}, 1, 0}, + {0x6F, (uint8_t[]){0x88}, 1, 0}, + + {0x75, (uint8_t[]){0xD9}, 1, 0}, + {0x76, (uint8_t[]){0x00}, 1, 0}, + {0x77, (uint8_t[]){0x33}, 1, 0}, + {0x78, (uint8_t[]){0x43}, 1, 0}, + + {0xE0, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 1, 120}, + + {0x29, (uint8_t[]){0x00}, 1, 20}, + {0x35, (uint8_t[]){0x00}, 1, 0}, +}; +#endif + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.json b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.json new file mode 100644 index 0000000..927bb97 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/config.json @@ -0,0 +1,29 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "waveshare-p4-wifi6-touch-lcd-xc-3.4c", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_LCD_TYPE_800_800_3_4_INCH=y", + "CONFIG_CAMERA_OV5647=y", + "CONFIG_CAMERA_OV5647_AUTO_DETECT_MIPI_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5647_MIPI_RAW8_800X800_50FPS=y", + "CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP=y" + ] + }, + { + "name": "waveshare-p4-wifi6-touch-lcd-xc-4c", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y", + "CONFIG_LCD_TYPE_720_720_4_INCH=y", + "CONFIG_CAMERA_OV5647=y", + "CONFIG_CAMERA_OV5647_AUTO_DETECT_MIPI_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5647_MIPI_RAW8_800X800_50FPS=y", + "CONFIG_XIAOZHI_ENABLE_CAMERA_ENDIANNESS_SWAP=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-p4-wifi6-touch-lcd-xc/esp32-p4-wifi6-touch-lcd-xc.cc b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/esp32-p4-wifi6-touch-lcd-xc.cc new file mode 100644 index 0000000..94cff60 --- /dev/null +++ b/main/boards/waveshare-p4-wifi6-touch-lcd-xc/esp32-p4-wifi6-touch-lcd-xc.cc @@ -0,0 +1,227 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "display/lcd_display.h" +// #include "display/no_display.h" +#include "button.h" + +#include "esp32_camera.h" +#include "esp_video_init.h" +#include "esp_cam_sensor_xclk.h" + +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" + +#include "esp_lcd_jd9365_10_1.h" +#include "config.h" + +#include +#include +#include +#include +#include "esp_lcd_touch_gt911.h" +#define TAG "WaveshareEsp32p4xc" + +class WaveshareEsp32p4xc : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay *display_; + Esp32Camera* camera_ = nullptr; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power(void) { +#if MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + // Turn on the power for MIPI DSI PHY, so it can go from "No Power" state to "Shutdown" state + static esp_ldo_channel_handle_t phy_pwr_chan = NULL; + esp_ldo_channel_config_t ldo_cfg = { + .chan_id = MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + esp_ldo_acquire_channel(&ldo_cfg, &phy_pwr_chan); + ESP_LOGI(TAG, "MIPI DSI PHY Powered on"); +#endif // BSP_MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + + return ESP_OK; + } + + void InitializeLCD() { + bsp_enable_dsi_phy_power(); + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 1500, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_config = JD9365_PANEL_IO_DBI_CONFIG(); + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 46, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 1, + .video_timing = { + .h_size = DISPLAY_WIDTH, + .v_size = DISPLAY_HEIGHT, + .hsync_pulse_width = 20, + .hsync_back_porch = 20, + .hsync_front_porch = 40, + .vsync_pulse_width = 4, + .vsync_back_porch = 12, + .vsync_front_porch = 24, + }, + .flags = { + .use_dma2d = true, + }, + }; + jd9365_vendor_config_t vendor_config = { + .init_cmds = lcd_init_cmds, + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]), + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + .lane_num = 2, + }, + .flags = { + .use_mipi_interface = 1, + }, + }; + + const esp_lcd_panel_dev_config_t lcd_dev_config = { + .reset_gpio_num = PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_jd9365(io, &lcd_dev_config, &disp_panel); + esp_lcd_panel_reset(disp_panel); + esp_lcd_panel_init(disp_panel); + + display_ = new MipiLcdDisplay(io, disp_panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_23, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + void InitializeCamera() { + esp_video_init_csi_config_t base_csi_config = { + .sccb_config = { + .init_sccb = false, + .i2c_handle = i2c_bus_, + .freq = 400000, + }, + .reset_pin = GPIO_NUM_NC, + .pwdn_pin = GPIO_NUM_NC, + }; + + esp_video_init_config_t cam_config = { + .csi = &base_csi_config, + }; + + camera_ = new Esp32Camera(cam_config); + } + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + +public: + WaveshareEsp32p4xc() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeLCD(); + InitializeTouch(); + InitializeCamera(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Camera* GetCamera() override { + return camera_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(WaveshareEsp32p4xc); diff --git a/main/boards/waveshare-s3-audio-board/README.md b/main/boards/waveshare-s3-audio-board/README.md new file mode 100644 index 0000000..dff4acc --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-AUDIO-Board +产品链接: +https://www.waveshare.net/shop/ESP32-S3-AUDIO-Board.htm \ No newline at end of file diff --git a/main/boards/waveshare-s3-audio-board/config.h b/main/boards/waveshare-s3-audio-board/config.h new file mode 100644 index 0000000..958cb89 --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/config.h @@ -0,0 +1,95 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define BUILTIN_LED_GPIO GPIO_NUM_38 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_16 +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define I2C_SCL_IO GPIO_NUM_10 +#define I2C_SDA_IO GPIO_NUM_11 + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_000 + +#define DISPLAY_SDA_PIN I2C_SDA_IO +#define DISPLAY_SCL_PIN I2C_SCL_IO + +#define DISPLAY_MISO_PIN GPIO_NUM_8 +#define DISPLAY_MOSI_PIN GPIO_NUM_9 +#define DISPLAY_SCLK_PIN GPIO_NUM_4 +#define DISPLAY_CS_PIN GPIO_NUM_3 +#define DISPLAY_DC_PIN GPIO_NUM_7 +#define DISPLAY_RESET_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_5 + +#define DISPLAY_SPI_SCLK_HZ (20 * 1000 * 1000) + +/* Camera pins */ +#define CAMERA_PIN_PWDN GPIO_NUM_NC +#define CAMERA_PIN_RESET GPIO_NUM_NC +#define CAMERA_PIN_XCLK GPIO_NUM_43 +#define CAMERA_PIN_SIOD GPIO_NUM_NC +#define CAMERA_PIN_SIOC GPIO_NUM_NC + +#define CAMERA_PIN_D7 GPIO_NUM_48 +#define CAMERA_PIN_D6 GPIO_NUM_47 +#define CAMERA_PIN_D5 GPIO_NUM_46 +#define CAMERA_PIN_D4 GPIO_NUM_45 +#define CAMERA_PIN_D3 GPIO_NUM_39 +#define CAMERA_PIN_D2 GPIO_NUM_18 +#define CAMERA_PIN_D1 GPIO_NUM_17 +#define CAMERA_PIN_D0 GPIO_NUM_2 +#define CAMERA_PIN_VSYNC GPIO_NUM_21 +#define CAMERA_PIN_HREF GPIO_NUM_1 +#define CAMERA_PIN_PCLK GPIO_NUM_44 + +#define XCLK_FREQ_HZ 20000000 + + + + +#ifdef CONFIG_AUDIO_BOARD_LCD_JD9853 +#define LCD_TYPE_JD9853_SERIAL +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 172 + +#define DISPLAY_SWAP_XY true +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_INVERT_COLOR true +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#endif + +#ifdef CONFIG_AUDIO_BOARD_LCD_ST7789 +#define LCD_TYPE_ST7789_SERIAL +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 320 + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_INVERT_COLOR true +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#endif + + + +#endif // _BOARD_CONFIG_H_ \ No newline at end of file diff --git a/main/boards/waveshare-s3-audio-board/config.json b/main/boards/waveshare-s3-audio-board/config.json new file mode 100644 index 0000000..c1c776b --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/config.json @@ -0,0 +1,19 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-audio-board", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y", + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_640X480_6FPS=y", + "CONFIG_CAMERA_OV2640_DVP_IF_FORMAT_INDEX_DEFAULT=1", + "CONFIG_CAMERA_OV5640=y", + "CONFIG_CAMERA_OV5640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5640_DVP_YUV422_800X600_10FPS=y", + "CONFIG_CAMERA_OV5640_DVP_IF_FORMAT_INDEX_DEFAULT=0" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-audio-board/esp32-s3-audio_board.cc b/main/boards/waveshare-s3-audio-board/esp32-s3-audio_board.cc new file mode 100644 index 0000000..85948c6 --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/esp32-s3-audio_board.cc @@ -0,0 +1,239 @@ +#include "wifi_board.h" +#include "codecs/box_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include +#include +#include "esp_io_expander_tca95xx_16bit.h" +#include "esp32_camera.h" +#include "led/circular_strip.h" +#include "esp_lcd_jd9853.h" + +#define TAG "waveshare_s3_audio_board" + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x0BULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +class CustomBoard : public WifiBoard { +private: + Button boot_button_; + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + Esp32Camera* camera_; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = I2C_SDA_IO, + .scl_io_num = I2C_SCL_IO, + .clk_source = I2C_CLK_SRC_DEFAULT, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9555(void) + { + esp_err_t ret = esp_io_expander_new_i2c_tca95xx_16bit(i2c_bus_, I2C_ADDRESS, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); // 打印引脚状态 + + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1 | IO_EXPANDER_PIN_NUM_8|IO_EXPANDER_PIN_NUM_5|IO_EXPANDER_PIN_NUM_6, IO_EXPANDER_OUTPUT); // 设置引脚 EXIO0 和 EXIO1 模式为输出 + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(10)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(10)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 1); // 复位 LCD 与 TouchPad + ESP_ERROR_CHECK(ret); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_8, 1); // 启用喇叭功放 + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_5, false); // 复位摄像头 + vTaskDelay(pdMS_TO_TICKS(5)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_6, true); + vTaskDelay(pdMS_TO_TICKS(5)); + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR)); + + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeJd9853Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = DISPLAY_SPI_SCLK_HZ; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片JD9853 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = GPIO_NUM_NC; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + //ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_new_panel_jd9853(panel_io, &panel_config, &panel)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, true)); + ESP_ERROR_CHECK(esp_lcd_panel_set_gap(panel, 0, 34)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, true, false)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, true)); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAMERA_PIN_D0, + [1] = CAMERA_PIN_D1, + [2] = CAMERA_PIN_D2, + [3] = CAMERA_PIN_D3, + [4] = CAMERA_PIN_D4, + [5] = CAMERA_PIN_D5, + [6] = CAMERA_PIN_D6, + [7] = CAMERA_PIN_D7, + }, + .vsync_io = CAMERA_PIN_VSYNC, + .de_io = CAMERA_PIN_HREF, + .pclk_io = CAMERA_PIN_PCLK, + .xclk_io = CAMERA_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, // 不初始化新的 SCCB,使用现有的 I2C 总线 + .i2c_handle = i2c_bus_, // 使用现有的 I2C 总线句柄 + .freq = 100000, // 100kHz + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAMERA_PIN_RESET, + .pwdn_pin = CAMERA_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = 12000000, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + + } +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeI2c(); + InitializeTca9555(); + InitializeSpi(); + InitializeButtons(); + #ifdef LCD_TYPE_JD9853_SERIAL + InitializeJd9853Display(); + #else + InitializeSt7789Display(); + #endif + InitializeCamera(); + GetBacklight()->RestoreBrightness(); + } + + virtual Led* GetLed() override { + static CircularStrip led(BUILTIN_LED_GPIO, 6); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec(i2c_bus_, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR, AUDIO_CODEC_ES7210_ADDR, AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, BACKLIGHT_INVERT); + return &backlight; + } + + virtual Camera* GetCamera() override { + return camera_; + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.c b/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.c new file mode 100644 index 0000000..dea68f2 --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.c @@ -0,0 +1,460 @@ +#include +#include "esp_lcd_jd9853.h" +/* + * SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "esp_lcd_panel_interface.h" +#include "esp_lcd_panel_io.h" +#include "esp_lcd_panel_vendor.h" +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_panel_commands.h" +#include "driver/gpio.h" +#include "esp_log.h" +#include "esp_check.h" + +static const char *TAG = "JD9853"; + +static esp_err_t panel_jd9853_del(esp_lcd_panel_t *panel); +static esp_err_t panel_jd9853_reset(esp_lcd_panel_t *panel); +static esp_err_t panel_jd9853_init(esp_lcd_panel_t *panel); +static esp_err_t panel_jd9853_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data); +static esp_err_t panel_jd9853_invert_color(esp_lcd_panel_t *panel, bool invert_color_data); +static esp_err_t panel_jd9853_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y); +static esp_err_t panel_jd9853_swap_xy(esp_lcd_panel_t *panel, bool swap_axes); +static esp_err_t panel_jd9853_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap); +static esp_err_t panel_jd9853_disp_on_off(esp_lcd_panel_t *panel, bool off); + +typedef struct +{ + esp_lcd_panel_t base; + esp_lcd_panel_io_handle_t io; + int reset_gpio_num; + bool reset_level; + int x_gap; + int y_gap; + uint8_t fb_bits_per_pixel; + uint8_t madctl_val; // save current value of LCD_CMD_MADCTL register + uint8_t colmod_val; // save current value of LCD_CMD_COLMOD register + const jd9853_lcd_init_cmd_t *init_cmds; + uint16_t init_cmds_size; +} jd9853_panel_t; + +esp_err_t esp_lcd_new_panel_jd9853(const esp_lcd_panel_io_handle_t io, const esp_lcd_panel_dev_config_t *panel_dev_config, esp_lcd_panel_handle_t *ret_panel) +{ + esp_err_t ret = ESP_OK; + jd9853_panel_t *jd9853 = NULL; + gpio_config_t io_conf = {0}; + + ESP_GOTO_ON_FALSE(io && panel_dev_config && ret_panel, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument"); + jd9853 = (jd9853_panel_t *)calloc(1, sizeof(jd9853_panel_t)); + ESP_GOTO_ON_FALSE(jd9853, ESP_ERR_NO_MEM, err, TAG, "no mem for jd9853 panel"); + + if (panel_dev_config->reset_gpio_num >= 0) + { + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = 1ULL << panel_dev_config->reset_gpio_num; + ESP_GOTO_ON_ERROR(gpio_config(&io_conf), err, TAG, "configure GPIO for RST line failed"); + } + +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + switch (panel_dev_config->color_space) + { + case ESP_LCD_COLOR_SPACE_RGB: + jd9853->madctl_val = 0; + break; + case ESP_LCD_COLOR_SPACE_BGR: + jd9853->madctl_val |= LCD_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported color space"); + break; + } +#else + switch (panel_dev_config->rgb_endian) + { + case LCD_RGB_ENDIAN_RGB: + jd9853->madctl_val = 0; + break; + case LCD_RGB_ENDIAN_BGR: + jd9853->madctl_val |= LCD_CMD_BGR_BIT; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported rgb endian"); + break; + } +#endif + + switch (panel_dev_config->bits_per_pixel) + { + case 16: // RGB565 + jd9853->colmod_val = 0x55; + jd9853->fb_bits_per_pixel = 16; + break; + case 18: // RGB666 + jd9853->colmod_val = 0x66; + // each color component (R/G/B) should occupy the 6 high bits of a byte, which means 3 full bytes are required for a pixel + jd9853->fb_bits_per_pixel = 24; + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "unsupported pixel width"); + break; + } + + jd9853->io = io; + jd9853->reset_gpio_num = panel_dev_config->reset_gpio_num; + jd9853->reset_level = panel_dev_config->flags.reset_active_high; + if (panel_dev_config->vendor_config) + { + jd9853->init_cmds = ((jd9853_vendor_config_t *)panel_dev_config->vendor_config)->init_cmds; + jd9853->init_cmds_size = ((jd9853_vendor_config_t *)panel_dev_config->vendor_config)->init_cmds_size; + } + jd9853->base.del = panel_jd9853_del; + jd9853->base.reset = panel_jd9853_reset; + jd9853->base.init = panel_jd9853_init; + jd9853->base.draw_bitmap = panel_jd9853_draw_bitmap; + jd9853->base.invert_color = panel_jd9853_invert_color; + jd9853->base.set_gap = panel_jd9853_set_gap; + jd9853->base.mirror = panel_jd9853_mirror; + jd9853->base.swap_xy = panel_jd9853_swap_xy; +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + jd9853->base.disp_off = panel_jd9853_disp_on_off; +#else + jd9853->base.disp_on_off = panel_jd9853_disp_on_off; +#endif + *ret_panel = &(jd9853->base); + ESP_LOGD(TAG, "new jd9853 panel @%p", jd9853); + + // ESP_LOGI(TAG, "LCD panel create success, version: %d.%d.%d", ESP_LCD_jd9853_VER_MAJOR, ESP_LCD_jd9853_VER_MINOR, + // ESP_LCD_jd9853_VER_PATCH); + + return ESP_OK; + +err: + if (jd9853) + { + if (panel_dev_config->reset_gpio_num >= 0) + { + gpio_reset_pin(panel_dev_config->reset_gpio_num); + } + free(jd9853); + } + return ret; +} + +static esp_err_t panel_jd9853_del(esp_lcd_panel_t *panel) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + + if (jd9853->reset_gpio_num >= 0) + { + gpio_reset_pin(jd9853->reset_gpio_num); + } + ESP_LOGD(TAG, "del jd9853 panel @%p", jd9853); + free(jd9853); + return ESP_OK; +} + +static esp_err_t panel_jd9853_reset(esp_lcd_panel_t *panel) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + + // perform hardware reset + if (jd9853->reset_gpio_num >= 0) + { + gpio_set_level(jd9853->reset_gpio_num, jd9853->reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(jd9853->reset_gpio_num, !jd9853->reset_level); + vTaskDelay(pdMS_TO_TICKS(10)); + } + else + { // perform software reset + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SWRESET, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(20)); // spec, wait at least 5ms before sending new command + } + + return ESP_OK; +} + +typedef struct +{ + uint8_t cmd; + uint8_t data[16]; + uint8_t data_bytes; // Length of data in above data array; 0xFF = end of cmds. +} lcd_init_cmd_t; + +// static const jd9853_lcd_init_cmd_t vendor_specific_init_default[] = { +// // {cmd, { data }, data_size, delay_ms} +// /* Power contorl B, power control = 0, DC_ENA = 1 */ +// {0xCF, (uint8_t []){0x00, 0xAA, 0XE0}, 3, 0}, +// /* Power on sequence control, +// * cp1 keeps 1 frame, 1st frame enable +// * vcl = 0, ddvdh=3, vgh=1, vgl=2 +// * DDVDH_ENH=1 +// */ +// {0xED, (uint8_t []){0x67, 0x03, 0X12, 0X81}, 4, 0}, +// /* Driver timing control A, +// * non-overlap=default +1 +// * EQ=default - 1, CR=default +// * pre-charge=default - 1 +// */ +// {0xE8, (uint8_t []){0x8A, 0x01, 0x78}, 3, 0}, +// /* Power control A, Vcore=1.6V, DDVDH=5.6V */ +// {0xCB, (uint8_t []){0x39, 0x2C, 0x00, 0x34, 0x02}, 5, 0}, +// /* Pump ratio control, DDVDH=2xVCl */ +// {0xF7, (uint8_t []){0x20}, 1, 0}, + +// {0xF7, (uint8_t []){0x20}, 1, 0}, +// /* Driver timing control, all=0 unit */ +// {0xEA, (uint8_t []){0x00, 0x00}, 2, 0}, +// /* Power control 1, GVDD=4.75V */ +// {0xC0, (uint8_t []){0x23}, 1, 0}, +// /* Power control 2, DDVDH=VCl*2, VGH=VCl*7, VGL=-VCl*3 */ +// {0xC1, (uint8_t []){0x11}, 1, 0}, +// /* VCOM control 1, VCOMH=4.025V, VCOML=-0.950V */ +// {0xC5, (uint8_t []){0x43, 0x4C}, 2, 0}, +// /* VCOM control 2, VCOMH=VMH-2, VCOML=VML-2 */ +// {0xC7, (uint8_t []){0xA0}, 1, 0}, +// /* Frame rate control, f=fosc, 70Hz fps */ +// {0xB1, (uint8_t []){0x00, 0x1B}, 2, 0}, +// /* Enable 3G, disabled */ +// {0xF2, (uint8_t []){0x00}, 1, 0}, +// /* Gamma set, curve 1 */ +// {0x26, (uint8_t []){0x01}, 1, 0}, +// /* Positive gamma correction */ +// {0xE0, (uint8_t []){0x1F, 0x36, 0x36, 0x3A, 0x0C, 0x05, 0x4F, 0X87, 0x3C, 0x08, 0x11, 0x35, 0x19, 0x13, 0x00}, 15, 0}, +// /* Negative gamma correction */ +// {0xE1, (uint8_t []){0x00, 0x09, 0x09, 0x05, 0x13, 0x0A, 0x30, 0x78, 0x43, 0x07, 0x0E, 0x0A, 0x26, 0x2C, 0x1F}, 15, 0}, +// /* Entry mode set, Low vol detect disabled, normal display */ +// {0xB7, (uint8_t []){0x07}, 1, 0}, +// /* Display function control */ +// {0xB6, (uint8_t []){0x08, 0x82, 0x27}, 3, 0}, +// }; + +static const jd9853_lcd_init_cmd_t vendor_specific_init_default[] = { + {0x11, (uint8_t []){ 0x00 }, 0, 120}, + {0xDF, (uint8_t[]){0x98, 0x53}, 2, 0}, + {0xDF, (uint8_t[]){0x98, 0x53}, 2, 0}, + {0xB2, (uint8_t[]){0x23}, 1, 0}, + {0xB7, (uint8_t[]){0x00, 0x47, 0x00, 0x6F}, 4, 0}, + {0xBB, (uint8_t[]){0x1C, 0x1A, 0x55, 0x73, 0x63, 0xF0}, 6, 0}, + {0xC0, (uint8_t[]){0x44, 0xA4}, 2, 0}, + {0xC1, (uint8_t[]){0x16}, 1, 0}, + {0xC3, (uint8_t[]){0x7D, 0x07, 0x14, 0x06, 0xCF, 0x71, 0x72, 0x77}, 8, 0}, + {0xC4, (uint8_t[]){0x00, 0x00, 0xA0, 0x79, 0x0B, 0x0A, 0x16, 0x79, 0x0B, 0x0A, 0x16, 0x82}, 12, 0}, // 00=60Hz 06=57Hz 08=51Hz, LN=320 Line + {0xC8, (uint8_t[]){0x3F, 0x32, 0x29, 0x29, 0x27, 0x2B, 0x27, 0x28, 0x28, 0x26, 0x25, 0x17, 0x12, 0x0D, 0x04, 0x00, 0x3F, 0x32, 0x29, 0x29, 0x27, 0x2B, 0x27, 0x28, 0x28, 0x26, 0x25, 0x17, 0x12, 0x0D, 0x04, 0x00}, 32, 0}, // SET_R_GAMMA + {0xD0, (uint8_t[]){0x04, 0x06, 0x6B, 0x0F, 0x00}, 5, 0}, + {0xD7, (uint8_t[]){0x00, 0x30}, 2, 0}, + {0xE6, (uint8_t[]){0x14}, 1, 0}, + {0xDE, (uint8_t[]){0x01}, 1, 0}, + {0xB7, (uint8_t[]){0x03, 0x13, 0xEF, 0x35, 0x35}, 5, 0}, + {0xC1, (uint8_t[]){0x14, 0x15, 0xC0}, 3, 0}, + {0xC2, (uint8_t[]){0x06, 0x3A}, 2, 0}, + {0xC4, (uint8_t[]){0x72, 0x12}, 2, 0}, + {0xBE, (uint8_t[]){0x00}, 1, 0}, + {0xDE, (uint8_t[]){0x02}, 1, 0}, + {0xE5, (uint8_t[]){0x00, 0x02, 0x00}, 3, 0}, + {0xE5, (uint8_t[]){0x01, 0x02, 0x00}, 3, 0}, + {0xDE, (uint8_t[]){0x00}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 1, 0}, + {0x3A, (uint8_t[]){0x05}, 1, 0}, // 06=RGB666;05=RGB565 + {0x2A, (uint8_t[]){0x00, 0x22, 0x00, 0xCD}, 4, 0}, // Start_X=34, End_X=205 + {0x2B, (uint8_t[]){0x00, 0x00, 0x01, 0x3F}, 4, 0}, // Start_Y=0, End_Y=319 + {0xDE, (uint8_t[]){0x02}, 1, 0}, + {0xE5, (uint8_t[]){0x00, 0x02, 0x00}, 3, 0}, + {0xDE, (uint8_t[]){0x00}, 1, 0}, + {0x29, (uint8_t []){ 0x00 }, 0, 0}, +}; + +static esp_err_t panel_jd9853_init(esp_lcd_panel_t *panel) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + + // LCD goes into sleep mode and display will be turned off after power on reset, exit sleep mode first + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_SLPOUT, NULL, 0), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(100)); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){ + jd9853->madctl_val, + }, + 1), + TAG, "send command failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_COLMOD, (uint8_t[]){ + jd9853->colmod_val, + }, + 1), + TAG, "send command failed"); + + const jd9853_lcd_init_cmd_t *init_cmds = NULL; + uint16_t init_cmds_size = 0; + if (jd9853->init_cmds) + { + init_cmds = jd9853->init_cmds; + init_cmds_size = jd9853->init_cmds_size; + } + else + { + init_cmds = vendor_specific_init_default; + init_cmds_size = sizeof(vendor_specific_init_default) / sizeof(jd9853_lcd_init_cmd_t); + } + + bool is_cmd_overwritten = false; + for (int i = 0; i < init_cmds_size; i++) + { + // Check if the command has been used or conflicts with the internal + switch (init_cmds[i].cmd) + { + case LCD_CMD_MADCTL: + is_cmd_overwritten = true; + jd9853->madctl_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + case LCD_CMD_COLMOD: + is_cmd_overwritten = true; + jd9853->colmod_val = ((uint8_t *)init_cmds[i].data)[0]; + break; + default: + is_cmd_overwritten = false; + break; + } + + if (is_cmd_overwritten) + { + ESP_LOGW(TAG, "The %02Xh command has been used and will be overwritten by external initialization sequence", init_cmds[i].cmd); + } + + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, init_cmds[i].cmd, init_cmds[i].data, init_cmds[i].data_bytes), TAG, "send command failed"); + vTaskDelay(pdMS_TO_TICKS(init_cmds[i].delay_ms)); + } + ESP_LOGD(TAG, "send init commands success"); + + return ESP_OK; +} + +static esp_err_t panel_jd9853_draw_bitmap(esp_lcd_panel_t *panel, int x_start, int y_start, int x_end, int y_end, const void *color_data) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + assert((x_start < x_end) && (y_start < y_end) && "start position must be smaller than end position"); + esp_lcd_panel_io_handle_t io = jd9853->io; + + x_start += jd9853->x_gap; + x_end += jd9853->x_gap; + y_start += jd9853->y_gap; + y_end += jd9853->y_gap; + + // define an area of frame memory where MCU can access + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_CASET, (uint8_t[]){ + (x_start >> 8) & 0xFF, + x_start & 0xFF, + ((x_end - 1) >> 8) & 0xFF, + (x_end - 1) & 0xFF, + }, + 4), + TAG, "send command failed"); + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_RASET, (uint8_t[]){ + (y_start >> 8) & 0xFF, + y_start & 0xFF, + ((y_end - 1) >> 8) & 0xFF, + (y_end - 1) & 0xFF, + }, + 4), + TAG, "send command failed"); + // transfer frame buffer + size_t len = (x_end - x_start) * (y_end - y_start) * jd9853->fb_bits_per_pixel / 8; + esp_lcd_panel_io_tx_color(io, LCD_CMD_RAMWR, color_data, len); + + return ESP_OK; +} + +static esp_err_t panel_jd9853_invert_color(esp_lcd_panel_t *panel, bool invert_color_data) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + int command = 0; + if (invert_color_data) + { + command = LCD_CMD_INVON; + } + else + { + command = LCD_CMD_INVOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_jd9853_mirror(esp_lcd_panel_t *panel, bool mirror_x, bool mirror_y) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + if (mirror_x) + { + jd9853->madctl_val |= LCD_CMD_MX_BIT; + } + else + { + jd9853->madctl_val &= ~LCD_CMD_MX_BIT; + } + if (mirror_y) + { + jd9853->madctl_val |= LCD_CMD_MY_BIT; + } + else + { + jd9853->madctl_val &= ~LCD_CMD_MY_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){jd9853->madctl_val}, 1), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_jd9853_swap_xy(esp_lcd_panel_t *panel, bool swap_axes) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + if (swap_axes) + { + jd9853->madctl_val |= LCD_CMD_MV_BIT; + } + else + { + jd9853->madctl_val &= ~LCD_CMD_MV_BIT; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, LCD_CMD_MADCTL, (uint8_t[]){jd9853->madctl_val}, 1), TAG, "send command failed"); + return ESP_OK; +} + +static esp_err_t panel_jd9853_set_gap(esp_lcd_panel_t *panel, int x_gap, int y_gap) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + jd9853->x_gap = x_gap; + jd9853->y_gap = y_gap; + return ESP_OK; +} + +static esp_err_t panel_jd9853_disp_on_off(esp_lcd_panel_t *panel, bool on_off) +{ + jd9853_panel_t *jd9853 = __containerof(panel, jd9853_panel_t, base); + esp_lcd_panel_io_handle_t io = jd9853->io; + int command = 0; + +#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0) + on_off = !on_off; +#endif + + if (on_off) + { + command = LCD_CMD_DISPON; + } + else + { + command = LCD_CMD_DISPOFF; + } + ESP_RETURN_ON_ERROR(esp_lcd_panel_io_tx_param(io, command, NULL, 0), TAG, "send command failed"); + return ESP_OK; +} diff --git a/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.h b/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.h new file mode 100644 index 0000000..487e749 --- /dev/null +++ b/main/boards/waveshare-s3-audio-board/esp_lcd_jd9853.h @@ -0,0 +1,102 @@ +/* + * SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * @file + * @brief ESP LCD: jd9853 + */ + +#pragma once + +#include "hal/spi_ll.h" +#include "esp_lcd_panel_vendor.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief LCD panel initialization commands. + * + */ +typedef struct { + int cmd; /* Board Type -> Waveshare ESP32-S3-ePaper-1.54 +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` + diff --git a/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.cc b/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.cc new file mode 100644 index 0000000..812d19f --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.cc @@ -0,0 +1,59 @@ +#include +#include +#include +#include "board_power_bsp.h" + +void BoardPowerBsp::PowerLedTask(void *arg) { + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = (0x1ULL << GPIO_NUM_3); + gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_conf.pull_up_en = GPIO_PULLUP_ENABLE; + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + for (;;) { + gpio_set_level(GPIO_NUM_3, 0); + vTaskDelay(pdMS_TO_TICKS(200)); + gpio_set_level(GPIO_NUM_3, 1); + // 不需要频繁闪烁,间隔指示效果更好 + vTaskDelay(pdMS_TO_TICKS(4800)); + } +} + +BoardPowerBsp::BoardPowerBsp(int epdPowerPin, int audioPowerPin, int vbatPowerPin) : epdPowerPin_(epdPowerPin), audioPowerPin_(audioPowerPin), vbatPowerPin_(vbatPowerPin) { + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = (0x1ULL << epdPowerPin_) | (0x1ULL << audioPowerPin_) | (0x1ULL << vbatPowerPin_); + gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_conf.pull_up_en = GPIO_PULLUP_ENABLE; + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + xTaskCreatePinnedToCore(PowerLedTask, "PowerLedTask", 3 * 1024, NULL, 2, NULL, 0); +} + +BoardPowerBsp::~BoardPowerBsp() { +} + +void BoardPowerBsp::PowerEpdOn() { + gpio_set_level((gpio_num_t) epdPowerPin_, 0); +} + +void BoardPowerBsp::PowerEpdOff() { + gpio_set_level((gpio_num_t) epdPowerPin_, 1); +} + +void BoardPowerBsp::PowerAudioOn() { + gpio_set_level((gpio_num_t) audioPowerPin_, 0); +} + +void BoardPowerBsp::PowerAudioOff() { + gpio_set_level((gpio_num_t) audioPowerPin_, 1); +} + +void BoardPowerBsp::VbatPowerOn() { + gpio_set_level((gpio_num_t) vbatPowerPin_, 1); +} + +void BoardPowerBsp::VbatPowerOff() { + gpio_set_level((gpio_num_t) vbatPowerPin_, 0); +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.h b/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.h new file mode 100644 index 0000000..1301168 --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/board_power_bsp.h @@ -0,0 +1,23 @@ +#ifndef __BOARD_POWER_BSP_H__ +#define __BOARD_POWER_BSP_H__ + +class BoardPowerBsp { +private: + const int epdPowerPin_; + const int audioPowerPin_; + const int vbatPowerPin_; + + static void PowerLedTask(void *arg); + +public: + BoardPowerBsp(int epdPowerPin, int audioPowerPin, int vbatPowerPin); + ~BoardPowerBsp(); + void PowerEpdOn(); + void PowerEpdOff(); + void PowerAudioOn(); + void PowerAudioOff(); + void VbatPowerOn(); + void VbatPowerOff(); +}; + +#endif \ No newline at end of file diff --git a/main/boards/waveshare-s3-epaper-1.54/config.h b/main/boards/waveshare-s3-epaper-1.54/config.h new file mode 100644 index 0000000..898f0ed --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/config.h @@ -0,0 +1,50 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_38 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_45 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VBAT_PWR_GPIO GPIO_NUM_18 + +/*EPD port Init*/ +#define EPD_SPI_NUM SPI3_HOST + +#define EPD_DC_PIN GPIO_NUM_10 +#define EPD_CS_PIN GPIO_NUM_11 +#define EPD_SCK_PIN GPIO_NUM_12 +#define EPD_MOSI_PIN GPIO_NUM_13 +#define EPD_RST_PIN GPIO_NUM_9 +#define EPD_BUSY_PIN GPIO_NUM_8 + +#define EXAMPLE_LCD_WIDTH 200 +#define EXAMPLE_LCD_HEIGHT 200 + +/*DEV POWER init*/ +#define EPD_PWR_PIN GPIO_NUM_6 +#define Audio_PWR_PIN GPIO_NUM_42 +#define VBAT_PWR_PIN GPIO_NUM_17 + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-epaper-1.54/config.json b/main/boards/waveshare-s3-epaper-1.54/config.json new file mode 100644 index 0000000..6bd7020 --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-epaper-1.54", + "sdkconfig_append": [ + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=partitions/v2/8m.csv", + "CONFIG_ESPTOOLPY_FLASHSIZE=8MB" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.cc b/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.cc new file mode 100644 index 0000000..1169c9e --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.cc @@ -0,0 +1,404 @@ +#include +#include +#include +#include +#include +#include "custom_lcd_display.h" +#include "board.h" +#include "config.h" +#include "esp_lvgl_port.h" +#include "settings.h" + +#define TAG "CustomLcdDisplay" + +#define BYTES_PER_PIXEL (LV_COLOR_FORMAT_GET_SIZE(LV_COLOR_FORMAT_RGB565)) +#define BUFF_SIZE (EXAMPLE_LCD_WIDTH * EXAMPLE_LCD_HEIGHT * BYTES_PER_PIXEL) + +const uint8_t WF_Full_1IN54[159] = +{ + 0x80,0x48,0x40,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x40,0x48,0x80,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x80,0x48,0x40,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x40,0x48,0x80,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0xA,0x0,0x0,0x0,0x0,0x0,0x0, + 0x8,0x1,0x0,0x8,0x1,0x0,0x2, + 0xA,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x22,0x22,0x22,0x22,0x22,0x22,0x0,0x0,0x0, + 0x22,0x17,0x41,0x0,0x32,0x20 +}; + +const uint8_t WF_PARTIAL_1IN54_0[159] = +{ + 0x0,0x40,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x80,0x80,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x40,0x40,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x80,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0xF,0x0,0x0,0x0,0x0,0x0,0x0, + 0x1,0x1,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x0,0x0,0x0,0x0,0x0,0x0,0x0, + 0x22,0x22,0x22,0x22,0x22,0x22,0x0,0x0,0x0, + 0x02,0x17,0x41,0xB0,0x32,0x28, +}; + +void CustomLcdDisplay::lvgl_flush_cb(lv_display_t *disp, const lv_area_t *area, uint8_t *color_p) { + assert(disp != NULL); + CustomLcdDisplay *driver = (CustomLcdDisplay *) lv_display_get_user_data(disp); + uint16_t *buffer = (uint16_t *) color_p; + driver->EPD_Clear(); + for (int y = area->y1; y <= area->y2; y++) { + for (int x = area->x1; x <= area->x2; x++) { + uint8_t color = (*buffer < 0x7fff) ? DRIVER_COLOR_BLACK : DRIVER_COLOR_WHITE; + driver->EPD_DrawColorPixel(x, y, color); + buffer++; + } + } + driver->EPD_DisplayPart(); + lv_disp_flush_ready(disp); +} + +CustomLcdDisplay::CustomLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy, custom_lcd_spi_t _lcd_spi_data) : + LcdDisplay(panel_io, panel, width, height), + lcd_spi_data(_lcd_spi_data), + Width(width), Height(height) { + + ESP_LOGI(TAG, "Initialize SPI"); + spi_port_init(); + spi_gpio_init(); + + ESP_LOGI(TAG, "Initialize LVGL library"); + lv_init(); + + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + port_cfg.task_priority = 2; + port_cfg.timer_period_ms = 50; + lvgl_port_init(&port_cfg); + lvgl_port_lock(0); + + buffer = (uint8_t *) heap_caps_malloc(lcd_spi_data.buffer_len, MALLOC_CAP_SPIRAM); + assert(buffer); + display_ = lv_display_create(width, height); /* 以水平和垂直分辨率(像素)进行基本初始化 */ + lv_display_set_flush_cb(display_, lvgl_flush_cb); + lv_display_set_user_data(display_, this); + + uint8_t *buffer_1 = NULL; + buffer_1 = (uint8_t *) heap_caps_malloc(BUFF_SIZE, MALLOC_CAP_SPIRAM); + assert(buffer_1); + lv_display_set_buffers(display_, buffer_1, NULL, BUFF_SIZE, LV_DISPLAY_RENDER_MODE_FULL); + + ESP_LOGI(TAG, "EPD init"); + EPD_Init(); + EPD_Clear(); + EPD_Display(); + EPD_DisplayPartBaseImage(); + EPD_Init_Partial(); // 局部刷新初始化 + + lvgl_port_unlock(); + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add display"); + return; + } + + ESP_LOGI(TAG, "ui start"); + + SetupUI(); +} + +CustomLcdDisplay::~CustomLcdDisplay() { + +} + +void CustomLcdDisplay::spi_gpio_init() { + int rst = lcd_spi_data.rst; + int cs = lcd_spi_data.cs; + int dc = lcd_spi_data.dc; + int busy = lcd_spi_data.busy; + + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = (0x1ULL << rst) | (0x1ULL << dc) | (0x1ULL << cs); + gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_conf.pull_up_en = GPIO_PULLUP_ENABLE; + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + + gpio_conf.mode = GPIO_MODE_INPUT; + gpio_conf.pin_bit_mask = (0x1ULL << busy); + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + + set_rst_1(); +} + +void CustomLcdDisplay::spi_port_init() { + int mosi = lcd_spi_data.mosi; + int scl = lcd_spi_data.scl; + int spi_host = lcd_spi_data.spi_host; + esp_err_t ret; + spi_bus_config_t buscfg = {}; + buscfg.miso_io_num = -1; + buscfg.mosi_io_num = mosi; + buscfg.sclk_io_num = scl; + buscfg.quadwp_io_num = -1; + buscfg.quadhd_io_num = -1; + buscfg.max_transfer_sz = Width * Height; + + spi_device_interface_config_t devcfg = {}; + devcfg.spics_io_num = -1; + devcfg.clock_speed_hz = 40 * 1000 * 1000; // Clock out at 10 MHz + devcfg.mode = 0; // SPI mode 0 + devcfg.queue_size = 7; // We want to be able to queue 7 transactions at a time + + ret = spi_bus_initialize((spi_host_device_t) spi_host, &buscfg, SPI_DMA_CH_AUTO); + ESP_ERROR_CHECK(ret); + ret = spi_bus_add_device((spi_host_device_t) spi_host, &devcfg, &spi); + ESP_ERROR_CHECK(ret); +} + +void CustomLcdDisplay::read_busy() { + int busy = lcd_spi_data.busy; + while (gpio_get_level((gpio_num_t) busy) == 1) { + vTaskDelay(pdMS_TO_TICKS(5)); // LOW: idle, HIGH: busy + } +} + +void CustomLcdDisplay::SPI_SendByte(uint8_t data) { + esp_err_t ret; + spi_transaction_t t; + memset(&t, 0, sizeof(t)); + t.length = 8; + t.tx_buffer = &data; + ret = spi_device_polling_transmit(spi, &t); // Transmit! + assert(ret == ESP_OK); // Should have had no issues. +} + +void CustomLcdDisplay::EPD_SendData(uint8_t data) { + set_dc_1(); + set_cs_0(); + SPI_SendByte(data); + set_cs_1(); +} + +void CustomLcdDisplay::EPD_SendCommand(uint8_t command) { + set_dc_0(); + set_cs_0(); + SPI_SendByte(command); + set_cs_1(); +} + +void CustomLcdDisplay::writeBytes(uint8_t *buffer, int len) { + set_dc_1(); + set_cs_0(); + esp_err_t ret; + spi_transaction_t t; + memset(&t, 0, sizeof(t)); + t.length = 8 * len; + t.tx_buffer = buffer; + ret = spi_device_polling_transmit(spi, &t); // Transmit! + assert(ret == ESP_OK); + set_cs_1(); +} + +void CustomLcdDisplay::writeBytes(const uint8_t *buffer, int len) { + set_dc_1(); + set_cs_0(); + esp_err_t ret; + spi_transaction_t t; + memset(&t, 0, sizeof(t)); + t.length = 8 * len; + t.tx_buffer = buffer; + ret = spi_device_polling_transmit(spi, &t); // Transmit! + assert(ret == ESP_OK); + set_cs_1(); +} + +void CustomLcdDisplay::EPD_SetWindows(uint16_t Xstart, uint16_t Ystart, uint16_t Xend, uint16_t Yend) { + EPD_SendCommand(0x44); // SET_RAM_X_ADDRESS_START_END_POSITION + EPD_SendData((Xstart >> 3) & 0xFF); + EPD_SendData((Xend >> 3) & 0xFF); + + EPD_SendCommand(0x45); // SET_RAM_Y_ADDRESS_START_END_POSITION + EPD_SendData(Ystart & 0xFF); + EPD_SendData((Ystart >> 8) & 0xFF); + EPD_SendData(Yend & 0xFF); + EPD_SendData((Yend >> 8) & 0xFF); +} + +void CustomLcdDisplay::EPD_SetCursor(uint16_t Xstart, uint16_t Ystart) { + EPD_SendCommand(0x4E); // SET_RAM_X_ADDRESS_COUNTER + EPD_SendData(Xstart & 0xFF); + + EPD_SendCommand(0x4F); // SET_RAM_Y_ADDRESS_COUNTER + EPD_SendData(Ystart & 0xFF); + EPD_SendData((Ystart >> 8) & 0xFF); +} + +void CustomLcdDisplay::EPD_SetLut(const uint8_t *lut) { + EPD_SendCommand(0x32); + writeBytes(lut, 153); + read_busy(); + + EPD_SendCommand(0x3f); + EPD_SendData(lut[153]); + + EPD_SendCommand(0x03); + EPD_SendData(lut[154]); + + EPD_SendCommand(0x04); + EPD_SendData(lut[155]); + EPD_SendData(lut[156]); + EPD_SendData(lut[157]); + + EPD_SendCommand(0x2c); + EPD_SendData(lut[158]); +} + +void CustomLcdDisplay::EPD_TurnOnDisplay() { + EPD_SendCommand(0x22); + EPD_SendData(0xc7); + EPD_SendCommand(0x20); + read_busy(); +} + +void CustomLcdDisplay::EPD_TurnOnDisplayPart() { + EPD_SendCommand(0x22); + EPD_SendData(0xcf); + EPD_SendCommand(0x20); + read_busy(); +} + +void CustomLcdDisplay::EPD_Init() { + set_rst_1(); + vTaskDelay(pdMS_TO_TICKS(50)); + set_rst_0(); + vTaskDelay(pdMS_TO_TICKS(20)); + set_rst_1(); + vTaskDelay(pdMS_TO_TICKS(50)); + + read_busy(); + EPD_SendCommand(0x12); // SWRESET + read_busy(); + + EPD_SendCommand(0x01); // Driver output control + EPD_SendData(0xC7); + EPD_SendData(0x00); + EPD_SendData(0x01); + + EPD_SendCommand(0x11); // data entry mode + EPD_SendData(0x01); + + EPD_SetWindows(0, Width - 1, Height - 1, 0); + + EPD_SendCommand(0x3C); // BorderWavefrom + EPD_SendData(0x01); + + EPD_SendCommand(0x18); + EPD_SendData(0x80); + + EPD_SendCommand(0x22); // Load Temperature and waveform setting. + EPD_SendData(0XB1); + EPD_SendCommand(0x20); + + EPD_SetCursor(0, Height - 1); + read_busy(); + + EPD_SetLut(WF_Full_1IN54); +} + +void CustomLcdDisplay::EPD_Clear() { + int buffer_len = lcd_spi_data.buffer_len; + memset(buffer, 0xff, buffer_len); +} + +void CustomLcdDisplay::EPD_Display() { + int buffer_len = lcd_spi_data.buffer_len; + EPD_SendCommand(0x24); + assert(buffer); + writeBytes(buffer, buffer_len); + EPD_TurnOnDisplay(); +} + +void CustomLcdDisplay::EPD_DisplayPartBaseImage() { + int buffer_len = lcd_spi_data.buffer_len; + EPD_SendCommand(0x24); + assert(buffer); + writeBytes(buffer, buffer_len); + EPD_SendCommand(0x26); + writeBytes(buffer, buffer_len); + EPD_TurnOnDisplay(); +} + +void CustomLcdDisplay::EPD_Init_Partial() { + set_rst_1(); + vTaskDelay(pdMS_TO_TICKS(50)); + set_rst_0(); + vTaskDelay(pdMS_TO_TICKS(20)); + set_rst_1(); + vTaskDelay(pdMS_TO_TICKS(50)); + + read_busy(); + + EPD_SetLut(WF_PARTIAL_1IN54_0); + + EPD_SendCommand(0x37); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x40); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x00); + EPD_SendData(0x00); + + EPD_SendCommand(0x3C); // BorderWavefrom + EPD_SendData(0x80); + + EPD_SendCommand(0x22); + EPD_SendData(0xc0); + EPD_SendCommand(0x20); + read_busy(); +} + +void CustomLcdDisplay::EPD_DisplayPart() { + EPD_SendCommand(0x24); + assert(buffer); + writeBytes(buffer, 5000); + EPD_TurnOnDisplayPart(); +} + +void CustomLcdDisplay::EPD_DrawColorPixel(uint16_t x, uint16_t y, uint8_t color) { + if (x >= Width || y >= Height) { + ESP_LOGE("EPD", "Out of bounds pixel: (%d,%d)", x, y); + return; + } + + uint16_t index = y * 25 + (x >> 3); + uint8_t bit = 7 - (x & 0x07); + if (color == DRIVER_COLOR_WHITE) { + buffer[index] |= (0x01 << bit); + } else { + buffer[index] &= ~(0x01 << bit); + } +} diff --git a/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.h b/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.h new file mode 100644 index 0000000..7a8f03e --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/custom_lcd_display.h @@ -0,0 +1,75 @@ +#ifndef __CUSTOM_LCD_DISPLAY_H__ +#define __CUSTOM_LCD_DISPLAY_H__ + +#include +#include "lcd_display.h" + +/* Display color */ +typedef enum { + DRIVER_COLOR_WHITE = 0xff, + DRIVER_COLOR_BLACK = 0x00, + FONT_BACKGROUND = DRIVER_COLOR_WHITE, +}COLOR_IMAGE; + +typedef struct { + uint8_t cs; + uint8_t dc; + uint8_t rst; + uint8_t busy; + uint8_t mosi; + uint8_t scl; + int spi_host; + int buffer_len; +}custom_lcd_spi_t; + + +class CustomLcdDisplay : public LcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy,custom_lcd_spi_t _lcd_spi_data); + ~CustomLcdDisplay(); + + void EPD_Init(); /* 墨水屏初始化 */ + void EPD_Clear(); /* 清空屏幕 */ + void EPD_Display(); /* 刷buffer到墨水屏 */ + + /*快速刷新*/ + void EPD_DisplayPartBaseImage(); + void EPD_Init_Partial(); + void EPD_DisplayPart(); + void EPD_DrawColorPixel(uint16_t x, uint16_t y,uint8_t color); + +private: + const custom_lcd_spi_t lcd_spi_data; + const int Width; + const int Height; + spi_device_handle_t spi; + uint8_t *buffer = NULL; + + static void lvgl_flush_cb(lv_display_t * disp, const lv_area_t * area, uint8_t * color_p); + + void spi_gpio_init(); + void spi_port_init(); + void read_busy(); + + void set_cs_1(){gpio_set_level((gpio_num_t)lcd_spi_data.cs,1);} + void set_cs_0(){gpio_set_level((gpio_num_t)lcd_spi_data.cs,0);} + void set_dc_1(){gpio_set_level((gpio_num_t)lcd_spi_data.dc,1);} + void set_dc_0(){gpio_set_level((gpio_num_t)lcd_spi_data.dc,0);} + void set_rst_1(){gpio_set_level((gpio_num_t)lcd_spi_data.rst,1);} + void set_rst_0(){gpio_set_level((gpio_num_t)lcd_spi_data.rst,0);} + + void SPI_SendByte(uint8_t data); + void EPD_SendData(uint8_t data); + void EPD_SendCommand(uint8_t command); + void writeBytes(uint8_t *buffer,int len); + void writeBytes(const uint8_t *buffer, int len); + void EPD_SetWindows(uint16_t Xstart, uint16_t Ystart, uint16_t Xend, uint16_t Yend); + void EPD_SetCursor(uint16_t Xstart, uint16_t Ystart); + void EPD_SetLut(const uint8_t *lut); + void EPD_TurnOnDisplay(); + void EPD_TurnOnDisplayPart(); +}; + +#endif // __CUSTOM_LCD_DISPLAY_H__ \ No newline at end of file diff --git a/main/boards/waveshare-s3-epaper-1.54/waveshare-s3-epaper-1.54.cc b/main/boards/waveshare-s3-epaper-1.54/waveshare-s3-epaper-1.54.cc new file mode 100644 index 0000000..a0c940b --- /dev/null +++ b/main/boards/waveshare-s3-epaper-1.54/waveshare-s3-epaper-1.54.cc @@ -0,0 +1,171 @@ +#include +#include +#include +#include +#include +#include "wifi_station.h" +#include "application.h" +#include "button.h" +#include "codecs/es8311_audio_codec.h" +#include "config.h" +#include "wifi_board.h" +#include "board_power_bsp.h" +#include "custom_lcd_display.h" +#include "lvgl.h" +#include "mcp_server.h" + +#define TAG "waveshare_epaper_1_54" + +class CustomBoard : public WifiBoard { + private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button pwr_button_; + CustomLcdDisplay *display_; + BoardPowerBsp *power_; + adc_oneshot_unit_handle_t adc1_handle; + adc_cali_handle_t cali_handle; + + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = {}; + i2c_bus_cfg.i2c_port = (i2c_port_t) 0; + i2c_bus_cfg.sda_io_num = AUDIO_CODEC_I2C_SDA_PIN; + i2c_bus_cfg.scl_io_num = AUDIO_CODEC_I2C_SCL_PIN; + i2c_bus_cfg.clk_source = I2C_CLK_SRC_DEFAULT; + i2c_bus_cfg.glitch_ignore_cnt = 7; + i2c_bus_cfg.intr_priority = 0; + i2c_bus_cfg.trans_queue_depth = 0; + i2c_bus_cfg.flags.enable_internal_pullup = 1; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto &app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + pwr_button_.OnLongPress([this]() { + GetDisplay()->SetChatMessage("system", "OFF"); + vTaskDelay(pdMS_TO_TICKS(1000)); + power_->PowerAudioOff(); + power_->PowerEpdOff(); + power_->VbatPowerOff(); + }); + } + + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.disp.network", "重新配网", PropertyList(), [this](const PropertyList &) -> ReturnValue { + ResetWifiConfiguration(); + return true; + }); + } + + void InitializeLcdDisplay() { + custom_lcd_spi_t lcd_spi_data = {}; + lcd_spi_data.cs = EPD_CS_PIN; + lcd_spi_data.dc = EPD_DC_PIN; + lcd_spi_data.rst = EPD_RST_PIN; + lcd_spi_data.busy = EPD_BUSY_PIN; + lcd_spi_data.mosi = EPD_MOSI_PIN; + lcd_spi_data.scl = EPD_SCK_PIN; + lcd_spi_data.spi_host = EPD_SPI_NUM; + lcd_spi_data.buffer_len = 5000; + display_ = new CustomLcdDisplay(NULL, NULL, EXAMPLE_LCD_WIDTH, EXAMPLE_LCD_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY, lcd_spi_data); + } + + void Power_Init() { + power_ = new BoardPowerBsp(EPD_PWR_PIN, Audio_PWR_PIN, VBAT_PWR_PIN); + power_->VbatPowerOn(); + power_->PowerAudioOn(); + power_->PowerEpdOn(); + do { + vTaskDelay(pdMS_TO_TICKS(10)); + } while (!gpio_get_level(VBAT_PWR_GPIO)); + } + + uint16_t BatterygetVoltage(void) { + static bool initialized = false; + static adc_oneshot_unit_handle_t adc_handle; + static adc_cali_handle_t cali_handle = NULL; + if (!initialized) { + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + }; + adc_oneshot_new_unit(&init_config, &adc_handle); + + adc_oneshot_chan_cfg_t ch_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + adc_oneshot_config_channel(adc_handle, ADC_CHANNEL_3, &ch_config); + + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = ADC_UNIT_1, + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + if (adc_cali_create_scheme_curve_fitting(&cali_config, &cali_handle) == ESP_OK) { + initialized = true; + } + } + + if (initialized) { + int raw_value = 0; + int raw_voltage = 0; + int voltage = 0; // mV + adc_oneshot_read(adc_handle, ADC_CHANNEL_3, &raw_value); + adc_cali_raw_to_voltage(cali_handle, raw_value, &raw_voltage); + voltage = raw_voltage * 2; + // ESP_LOGI(TAG, "voltage: %dmV", voltage); + return (uint16_t)voltage; + } + + return 0; + } + + uint8_t BatterygetPercent() { + int voltage = 0; + for (uint8_t i = 0; i < 10; i++) { + voltage += BatterygetVoltage(); + } + + voltage /= 10; + int percent = (-1 * voltage * voltage + 9016 * voltage - 19189000) / 10000; + percent = (percent > 100) ? 100 : (percent < 0) ? 0 : percent; + // ESP_LOGI(TAG, "voltage: %dmV, percentage: %d%%", voltage, percent); + return (uint8_t)percent; + } + + public: + CustomBoard() : boot_button_(BOOT_BUTTON_GPIO), pwr_button_(VBAT_PWR_GPIO) { + Power_Init(); + InitializeI2c(); + InitializeButtons(); + InitializeTools(); + InitializeLcdDisplay(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + charging = false; + discharging = !charging; + level = (int)BatterygetPercent(); + + return true; + } +}; + +DECLARE_BOARD(CustomBoard); \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-amoled-1.32/README.md b/main/boards/waveshare-s3-touch-amoled-1.32/README.md new file mode 100644 index 0000000..82eecd7 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.32/README.md @@ -0,0 +1,48 @@ +# 产品链接 + +[微雪电子 ESP32-S3-Touch-AMOLED-1.32](https://www.waveshare.net/shop/ESP32-S3-Touch-AMOLED-1.32.htm) + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +Xiaozhi Assistant -> Board Type -> Waveshare ESP32-S3-Touch-AMOLED-1.32 +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` + diff --git a/main/boards/waveshare-s3-touch-amoled-1.32/config.h b/main/boards/waveshare-s3-touch-amoled-1.32/config.h new file mode 100644 index 0000000..6534a6f --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.32/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_38 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_41 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_39 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_40 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_42 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_17 +#define PWR_EN_GPIO GPIO_NUM_18 + + +/*disp-qspi-lcd*/ +#define LCD_CS GPIO_NUM_10 +#define LCD_PCLK GPIO_NUM_11 +#define LCD_D0 GPIO_NUM_12 +#define LCD_D1 GPIO_NUM_13 +#define LCD_D2 GPIO_NUM_14 +#define LCD_D3 GPIO_NUM_15 +#define LCD_RST GPIO_NUM_8 +#define LCD_LIGHT (-1) + +#define EXAMPLE_LCD_H_RES 466 +#define EXAMPLE_LCD_V_RES 466 + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-amoled-1.32/config.json b/main/boards/waveshare-s3-touch-amoled-1.32/config.json new file mode 100644 index 0000000..9ab5221 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.32/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-amoled-1.32", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE=8MB", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=partitions/v2/8m.csv" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-amoled-1.32/esp32-s3-touch-amoled-1.32.cc b/main/boards/waveshare-s3-touch-amoled-1.32/esp32-s3-touch-amoled-1.32.cc new file mode 100644 index 0000000..5f8099e --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.32/esp32-s3-touch-amoled-1.32.cc @@ -0,0 +1,214 @@ +#include "application.h" +#include "button.h" +#include "codecs/es8311_audio_codec.h" +#include "config.h" +#include "wifi_board.h" + +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" +#include "lvgl.h" +#include "mcp_server.h" +#include +#include +#include +#include +#include + +#define TAG "waveshare_s3_amoled_1_32" + +static const sh8601_lcd_init_cmd_t lcd_init_cmds[] = { + {0xFE, (uint8_t[]) {0x00}, 1, 0}, + {0xC4, (uint8_t[]) {0x80}, 1, 0}, + {0x3A, (uint8_t[]) {0x55}, 1, 0}, // 0x55 for RGB565, 0x77 for RGB888 + {0x35, (uint8_t[]) {0x00}, 1, 0}, + {0x53, (uint8_t[]) {0x20}, 1, 0}, + {0x51, (uint8_t[]) {0xFF}, 1, 0}, // Brightness + {0x63, (uint8_t[]) {0xFF}, 1, 0}, + {0x2A, (uint8_t[]) {0x00, 0x06, 0x01, 0xD7}, 4, 0}, + {0x2B, (uint8_t[]) {0x00, 0x00, 0x01, 0xD1}, 4, 0}, + {0x11, (uint8_t[]) {0x00}, 0, 100}, + {0x29, (uint8_t[]) {0x00}, 0, 0}, +}; + +class CustomLcdDisplay : public SpiLcdDisplay { + private: + esp_lcd_panel_io_handle_t io_handle_; + + public: + static void my_draw_event_cb(lv_event_t *e) { + lv_area_t *area = (lv_area_t *) lv_event_get_param(e); + + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + + // Round area for better performance + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + void SetMIRROR_XY(uint8_t mirror) { + uint32_t lcd_cmd = 0x36; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= 0x02 << 24; + uint8_t param = mirror; + esp_lcd_panel_io_tx_param(io_handle_, lcd_cmd, ¶m, 1); + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, esp_lcd_panel_handle_t panel_handle, int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) : + SpiLcdDisplay(io_handle, panel_handle, width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy), + io_handle_(io_handle) { + DisplayLockGuard lock(this); + lv_display_add_event_cb(display_, my_draw_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + SetMIRROR_XY(0xC0); // Rotate 180 degrees + lv_obj_invalidate(lv_screen_active()); + } +}; + +class CustomBoard : public WifiBoard { + private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + Button pwr_button_; + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_panel_io_handle_t io_handle = NULL; + CustomLcdDisplay *display_; + lv_indev_t *touch_indev = NULL; + i2c_master_dev_handle_t disp_touch_dev_handle = NULL; + + void InitializeI2c() { + i2c_master_bus_config_t i2c_bus_cfg = {}; + i2c_bus_cfg.i2c_port = I2C_NUM_0; + i2c_bus_cfg.sda_io_num = AUDIO_CODEC_I2C_SDA_PIN; + i2c_bus_cfg.scl_io_num = AUDIO_CODEC_I2C_SCL_PIN; + i2c_bus_cfg.clk_source = I2C_CLK_SRC_DEFAULT; + i2c_bus_cfg.glitch_ignore_cnt = 7; + i2c_bus_cfg.intr_priority = 0; + i2c_bus_cfg.trans_queue_depth = 0; + i2c_bus_cfg.flags.enable_internal_pullup = 1; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void SetDispbacklight(uint8_t backlight) { + uint32_t lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= 0x02 << 24; + uint8_t param = backlight; + esp_lcd_panel_io_tx_param(io_handle, lcd_cmd, ¶m, 1); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto &app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + pwr_button_.OnLongPress([this]() { + GetDisplay()->SetChatMessage("system", "OFF"); + vTaskDelay(pdMS_TO_TICKS(1000)); + gpio_set_level(PWR_EN_GPIO, 0); + }); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.data0_io_num = LCD_D0; + buscfg.data1_io_num = LCD_D1; + buscfg.sclk_io_num = LCD_PCLK; + buscfg.data2_io_num = LCD_D2; + buscfg.data3_io_num = LCD_D3; + buscfg.max_transfer_sz = EXAMPLE_LCD_H_RES * EXAMPLE_LCD_V_RES * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = LCD_CS; + io_config.dc_gpio_num = -1; + io_config.spi_mode = 0; + io_config.pclk_hz = 40 * 1000 * 1000; + io_config.trans_queue_depth = 8; + io_config.on_color_trans_done = NULL; + io_config.user_ctx = NULL; + io_config.lcd_cmd_bits = 32; + io_config.lcd_param_bits = 8; + io_config.flags.quad_mode = true; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &io_handle)); + + sh8601_vendor_config_t vendor_config = {}; + vendor_config.init_cmds = lcd_init_cmds; + vendor_config.init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]); + vendor_config.flags.use_qspi_interface = 1; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(io_handle, &panel_config, &panel_handle)); + esp_lcd_panel_set_gap(panel_handle, 0x06, 0x00); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle)); + + display_ = new CustomLcdDisplay(io_handle, panel_handle, EXAMPLE_LCD_H_RES, EXAMPLE_LCD_V_RES, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.disp.setbacklight", "设置屏幕亮度", PropertyList({Property("level", kPropertyTypeInteger, 0, 255)}), [this](const PropertyList &properties) -> ReturnValue { + int level = properties["level"].value(); + ESP_LOGI("setbacklight", "%d", level); + SetDispbacklight(level); + return true; + }); + + mcp_server.AddTool("self.disp.network", "重新配网", PropertyList(), [this](const PropertyList &) -> ReturnValue { + ResetWifiConfiguration(); + return true; + }); + } + + void CheckPowerKeyState() { + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = (0x1ULL << PWR_EN_GPIO); + gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + gpio_conf.pull_up_en = GPIO_PULLUP_ENABLE; + ESP_ERROR_CHECK_WITHOUT_ABORT(gpio_config(&gpio_conf)); + gpio_set_level(PWR_EN_GPIO, 1); + do { + vTaskDelay(pdMS_TO_TICKS(10)); + } while (!gpio_get_level(PWR_BUTTON_GPIO)); + } + + public: + CustomBoard() : boot_button_(BOOT_BUTTON_GPIO), pwr_button_(PWR_BUTTON_GPIO) { + CheckPowerKeyState(); + InitializeI2c(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec *GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/waveshare-s3-touch-amoled-1.75/README.md b/main/boards/waveshare-s3-touch-amoled-1.75/README.md new file mode 100644 index 0000000..5f99392 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.75/README.md @@ -0,0 +1,15 @@ +# Waveshare ESP32-S3-Touch-AMOLED-1.75 + + +[ESP32-S3-Touch-AMOLED-1.75](https://www.waveshare.com/esp32-s3-touch-amoled-1.75.htm) ESP32-S3-Touch-AMOLED-1.75 is a high performance, highly integrated microcontroller development board designed by Waveshare.\ +In the smaller form, the 1.75-inch capacitive HD AMOLED screen, highly integrated power management chip, six-axis sensor (three-axis accelerometer and three-axis gyroscope), RTC, low-power audio codec chip and echo cancellation circuit are mounted on the board, which is convenient for development and embedding into the product. + + +## images + +| [ESP32-S3-Touch-AMOLED-1.75](https://www.waveshare.com/esp32-s3-touch-amoled-1.75.htm) | +|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| | +| | +| | + diff --git a/main/boards/waveshare-s3-touch-amoled-1.75/config.h b/main/boards/waveshare-s3-touch-amoled-1.75/config.h new file mode 100644 index 0000000..40ac5df --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.75/config.h @@ -0,0 +1,44 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_42 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define EXAMPLE_PIN_NUM_LCD_CS GPIO_NUM_12 +#define EXAMPLE_PIN_NUM_LCD_PCLK GPIO_NUM_38 +#define EXAMPLE_PIN_NUM_LCD_DATA0 GPIO_NUM_4 +#define EXAMPLE_PIN_NUM_LCD_DATA1 GPIO_NUM_5 +#define EXAMPLE_PIN_NUM_LCD_DATA2 GPIO_NUM_6 +#define EXAMPLE_PIN_NUM_LCD_DATA3 GPIO_NUM_7 +#define EXAMPLE_PIN_NUM_LCD_RST GPIO_NUM_39 +#define DISPLAY_WIDTH 466 +#define DISPLAY_HEIGHT 466 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-amoled-1.75/config.json b/main/boards/waveshare-s3-touch-amoled-1.75/config.json new file mode 100644 index 0000000..6e4e8ac --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.75/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-amoled-1.75", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-amoled-1.75/esp32-s3-touch-amoled-1.75.cc b/main/boards/waveshare-s3-touch-amoled-1.75/esp32-s3-touch-amoled-1.75.cc new file mode 100644 index 0000000..9053154 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-1.75/esp32-s3-touch-amoled-1.75.cc @@ -0,0 +1,361 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" + +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" +#include "settings.h" + +#include +#include +#include + +#define TAG "WaveshareEsp32s3TouchAMOLED1inch75" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x01); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x03ULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const sh8601_lcd_init_cmd_t vendor_specific_init[] = { + // set display to qspi mode + {0xFE, (uint8_t[]){0x20}, 1, 0}, + {0x19, (uint8_t[]){0x10}, 1, 0}, + {0x1C, (uint8_t[]){0xA0}, 1, 0}, + + {0xFE, (uint8_t[]){0x00}, 1, 0}, + {0xC4, (uint8_t[]){0x80}, 1, 0}, + {0x3A, (uint8_t[]){0x55}, 1, 0}, + {0x35, (uint8_t[]){0x00}, 1, 0}, + {0x53, (uint8_t[]){0x20}, 1, 0}, + {0x51, (uint8_t[]){0xFF}, 1, 0}, + {0x63, (uint8_t[]){0xFF}, 1, 0}, + {0x2A, (uint8_t[]){0x00, 0x06, 0x01, 0xD7}, 4, 0}, + {0x2B, (uint8_t[]){0x00, 0x00, 0x01, 0xD1}, 4, 600}, + {0x11, NULL, 0, 600}, + {0x29, NULL, 0, 0}, +}; + +// 在waveshare_amoled_1_75类之前添加新的显示类 +class CustomLcdDisplay : public SpiLcdDisplay { +public: + static void rounder_event_cb(lv_event_t* e) { + lv_area_t* area = (lv_area_t* )lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + + // round the start of coordinate down to the nearest 2M number + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + // round the end of coordinate up to the nearest 2N+1 number + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES* 0.1, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES* 0.1, 0); + lv_display_add_event_cb(display_, rounder_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(esp_lcd_panel_io_handle_t panel_io) : Backlight(), panel_io_(panel_io) {} + +protected: + esp_lcd_panel_io_handle_t panel_io_; + + virtual void SetBrightnessImpl(uint8_t brightness) override { + auto display = Board::GetInstance().GetDisplay(); + DisplayLockGuard lock(display); + uint8_t data[1] = {((uint8_t)((255* brightness) / 100))}; + int lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_WRITE_CMD << 24; + esp_lcd_panel_io_tx_param(panel_io_, lcd_cmd, &data, sizeof(data)); + } +}; + +class WaveshareEsp32s3TouchAMOLED1inch75 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + CustomLcdDisplay* display_; + CustomBacklight* backlight_; + esp_io_expander_handle_t io_expander = NULL; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); }); + power_save_timer_->OnShutdownRequest([this](){ + pmic_->PowerOff(); }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + if (ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_4, IO_EXPANDER_INPUT); + ESP_ERROR_CHECK(ret); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.sclk_io_num = EXAMPLE_PIN_NUM_LCD_PCLK; + buscfg.data0_io_num = EXAMPLE_PIN_NUM_LCD_DATA0; + buscfg.data1_io_num = EXAMPLE_PIN_NUM_LCD_DATA1; + buscfg.data2_io_num = EXAMPLE_PIN_NUM_LCD_DATA2; + buscfg.data3_io_num = EXAMPLE_PIN_NUM_LCD_DATA3; + buscfg.max_transfer_sz = DISPLAY_WIDTH* DISPLAY_HEIGHT* sizeof(uint16_t); + buscfg.flags = SPICOMMON_BUSFLAG_QUAD; + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeSH8601Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = SH8601_PANEL_IO_QSPI_CONFIG( + EXAMPLE_PIN_NUM_LCD_CS, + nullptr, + nullptr); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const sh8601_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(sh8601_lcd_init_cmd_t), + .flags = { + .use_qspi_interface = 1, + }}; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = EXAMPLE_PIN_NUM_LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void* )&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(panel_io, &panel_config, &panel)); + esp_lcd_panel_set_gap(panel, 0x06, 0); + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + backlight_ = new CustomBacklight(panel_io); + backlight_->RestoreBrightness(); + } + + void InitializeTouch() { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH - 1, + .y_max = DISPLAY_HEIGHT - 1, + .rst_gpio_num = GPIO_NUM_40, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 1, + .mirror_y = 1, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_CST9217_CONFIG(); + tp_io_config.scl_speed_hz = 400* 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_cst9217(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + WaveshareEsp32s3TouchAMOLED1inch75() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeTca9554(); + InitializeAxp2101(); + InitializeSpi(); + InitializeSH8601Display(); + InitializeTouch(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + return backlight_; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) + { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) + { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32s3TouchAMOLED1inch75); diff --git a/main/boards/waveshare-s3-touch-amoled-2.06/README.md b/main/boards/waveshare-s3-touch-amoled-2.06/README.md new file mode 100644 index 0000000..aa8bbe8 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-2.06/README.md @@ -0,0 +1,11 @@ +# Waveshare ESP32-S3-Touch-AMOLED-2.06 + + +[ESP32-S3-Touch-AMOLED-2.06](https://www.waveshare.com/esp32-s3-touch-amoled-2.06.htm) is a high-performance, wearable watch-style development board designed by Waveshare. Based on the ESP32-S3R8 microcontroller, it integrates a 2.06inch AMOLED capacitive touch display, 6-axis IMU, RTC chip, audio codec chip, power management IC, and so on. Comes with a custom-designed case with a smartwatch-like appearance, making it ideal for prototyping and functional verification of wearable applications. + +## images + +| [ESP32-S3-Touch-AMOLED-2.06](https://www.waveshare.com/esp32-s3-touch-amoled-2.06.htm) | +|------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| | + diff --git a/main/boards/waveshare-s3-touch-amoled-2.06/config.h b/main/boards/waveshare-s3-touch-amoled-2.06/config.h new file mode 100644 index 0000000..6ad75a7 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-2.06/config.h @@ -0,0 +1,43 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_41 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_42 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_40 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define EXAMPLE_PIN_NUM_LCD_CS GPIO_NUM_12 +#define EXAMPLE_PIN_NUM_LCD_PCLK GPIO_NUM_11 +#define EXAMPLE_PIN_NUM_LCD_DATA0 GPIO_NUM_4 +#define EXAMPLE_PIN_NUM_LCD_DATA1 GPIO_NUM_5 +#define EXAMPLE_PIN_NUM_LCD_DATA2 GPIO_NUM_6 +#define EXAMPLE_PIN_NUM_LCD_DATA3 GPIO_NUM_7 +#define EXAMPLE_PIN_NUM_LCD_RST GPIO_NUM_8 +#define DISPLAY_WIDTH 410 +#define DISPLAY_HEIGHT 502 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_NC +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-amoled-2.06/config.json b/main/boards/waveshare-s3-touch-amoled-2.06/config.json new file mode 100644 index 0000000..3a95f74 --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-2.06/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-amoled-2.06", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-amoled-2.06/esp32-s3-touch-amoled-2.06.cc b/main/boards/waveshare-s3-touch-amoled-2.06/esp32-s3-touch-amoled-2.06.cc new file mode 100644 index 0000000..15facfc --- /dev/null +++ b/main/boards/waveshare-s3-touch-amoled-2.06/esp32-s3-touch-amoled-2.06.cc @@ -0,0 +1,347 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "esp_lcd_sh8601.h" + +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "settings.h" + +#include +#include +#include + +#define TAG "WaveshareEsp32s3TouchAMOLED2inch06" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + WriteReg(0x93, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x03); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x0A); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x03ULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const sh8601_lcd_init_cmd_t vendor_specific_init[] = { + // set display to qspi mode + {0x11, (uint8_t []){0x00}, 0, 120}, + {0xC4, (uint8_t []){0x80}, 1, 0}, + {0x44, (uint8_t []){0x01, 0xD1}, 2, 0}, + {0x35, (uint8_t []){0x00}, 1, 0}, + {0x53, (uint8_t []){0x20}, 1, 10}, + {0x63, (uint8_t []){0xFF}, 1, 10}, + {0x51, (uint8_t []){0x00}, 1, 10}, + {0x2A, (uint8_t []){0x00,0x16,0x01,0xAF}, 4, 0}, + {0x2B, (uint8_t []){0x00,0x00,0x01,0xF5}, 4, 0}, + {0x29, (uint8_t []){0x00}, 0, 10}, + {0x51, (uint8_t []){0xFF}, 1, 0}, +}; + +// 在waveshare_amoled_2_06类之前添加新的显示类 +class CustomLcdDisplay : public SpiLcdDisplay { +public: + static void rounder_event_cb(lv_event_t* e) { + lv_area_t* area = (lv_area_t* )lv_event_get_param(e); + uint16_t x1 = area->x1; + uint16_t x2 = area->x2; + + uint16_t y1 = area->y1; + uint16_t y2 = area->y2; + + // round the start of coordinate down to the nearest 2M number + area->x1 = (x1 >> 1) << 1; + area->y1 = (y1 >> 1) << 1; + // round the end of coordinate up to the nearest 2N+1 number + area->x2 = ((x2 >> 1) << 1) + 1; + area->y2 = ((y2 >> 1) << 1) + 1; + } + + CustomLcdDisplay(esp_lcd_panel_io_handle_t io_handle, + esp_lcd_panel_handle_t panel_handle, + int width, + int height, + int offset_x, + int offset_y, + bool mirror_x, + bool mirror_y, + bool swap_xy) + : SpiLcdDisplay(io_handle, panel_handle, + width, height, offset_x, offset_y, mirror_x, mirror_y, swap_xy) { + DisplayLockGuard lock(this); + lv_obj_set_style_pad_left(status_bar_, LV_HOR_RES* 0.1, 0); + lv_obj_set_style_pad_right(status_bar_, LV_HOR_RES* 0.1, 0); + lv_display_add_event_cb(display_, rounder_event_cb, LV_EVENT_INVALIDATE_AREA, NULL); + } +}; + +class CustomBacklight : public Backlight { +public: + CustomBacklight(esp_lcd_panel_io_handle_t panel_io) : Backlight(), panel_io_(panel_io) {} + +protected: + esp_lcd_panel_io_handle_t panel_io_; + + virtual void SetBrightnessImpl(uint8_t brightness) override { + auto display = Board::GetInstance().GetDisplay(); + DisplayLockGuard lock(display); + uint8_t data[1] = {((uint8_t)((255* brightness) / 100))}; + int lcd_cmd = 0x51; + lcd_cmd &= 0xff; + lcd_cmd <<= 8; + lcd_cmd |= LCD_OPCODE_WRITE_CMD << 24; + esp_lcd_panel_io_tx_param(panel_io_, lcd_cmd, &data, sizeof(data)); + } +}; + +class WaveshareEsp32s3TouchAMOLED2inch06 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + CustomLcdDisplay* display_; + CustomBacklight* backlight_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); }); + power_save_timer_->OnShutdownRequest([this](){ + pmic_->PowerOff(); }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.sclk_io_num = EXAMPLE_PIN_NUM_LCD_PCLK; + buscfg.data0_io_num = EXAMPLE_PIN_NUM_LCD_DATA0; + buscfg.data1_io_num = EXAMPLE_PIN_NUM_LCD_DATA1; + buscfg.data2_io_num = EXAMPLE_PIN_NUM_LCD_DATA2; + buscfg.data3_io_num = EXAMPLE_PIN_NUM_LCD_DATA3; + buscfg.max_transfer_sz = DISPLAY_WIDTH* DISPLAY_HEIGHT* sizeof(uint16_t); + buscfg.flags = SPICOMMON_BUSFLAG_QUAD; + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeSH8601Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = SH8601_PANEL_IO_QSPI_CONFIG( + EXAMPLE_PIN_NUM_LCD_CS, + nullptr, + nullptr); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + const sh8601_vendor_config_t vendor_config = { + .init_cmds = &vendor_specific_init[0], + .init_cmds_size = sizeof(vendor_specific_init) / sizeof(sh8601_lcd_init_cmd_t), + .flags = { + .use_qspi_interface = 1, + }}; + + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = EXAMPLE_PIN_NUM_LCD_RST; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = (void* )&vendor_config; + ESP_ERROR_CHECK(esp_lcd_new_panel_sh8601(panel_io, &panel_config, &panel)); + esp_lcd_panel_set_gap(panel, 0x16, 0); + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, false); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + backlight_ = new CustomBacklight(panel_io); + backlight_->RestoreBrightness(); + } + + void InitializeTouch() { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH - 1, + .y_max = DISPLAY_HEIGHT - 1, + .rst_gpio_num = GPIO_NUM_9, + .int_gpio_num = GPIO_NUM_38, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_FT5x06_CONFIG(); + tp_io_config.scl_speed_hz = 400* 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_ft5x06(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + WaveshareEsp32s3TouchAMOLED2inch06() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeAxp2101(); + InitializeSpi(); + InitializeSH8601Display(); + InitializeTouch(); + InitializeButtons(); + InitializeTools(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + return backlight_; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) + { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) + { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32s3TouchAMOLED2inch06); diff --git a/main/boards/waveshare-s3-touch-lcd-1.83/README.md b/main/boards/waveshare-s3-touch-lcd-1.83/README.md new file mode 100644 index 0000000..f2d4377 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-1.83/README.md @@ -0,0 +1,4 @@ +# Waveshare ESP32-S3-Touch-LCD-1.83 + + +[ESP32-S3-Touch-LCD-1.83](https://www.waveshare.com/esp32-s3-touch-lcd-1.83.htm) ESP32-S3-Touch-LCD-1.83 is a high-performance and highly integrated microcontroller development board designed by Waveshare. With a compact board size, it is equipped with a 1.83-inch capacitive LCD screen, a highly integrated power management chip, six-axis sensors (three-axis accelerometer and three-axis gyroscope), RTC and low-power audio codec chip, etc., making it convenient for development and easy to be embedded in products. \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-1.83/config.h b/main/boards/waveshare-s3-touch-lcd-1.83/config.h new file mode 100644 index 0000000..97bba44 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-1.83/config.h @@ -0,0 +1,47 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_45 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_9 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_46 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_15 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_14 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_41 + +#define DISPLAY_SPI_MODE 3 +#define DISPLAY_CS_PIN GPIO_NUM_5 +#define DISPLAY_MOSI_PIN GPIO_NUM_7 +#define DISPLAY_MISO_PIN GPIO_NUM_NC +#define DISPLAY_CLK_PIN GPIO_NUM_6 +#define DISPLAY_DC_PIN GPIO_NUM_4 +#define DISPLAY_RST_PIN GPIO_NUM_38 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 284 +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_40 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-lcd-1.83/config.json b/main/boards/waveshare-s3-touch-lcd-1.83/config.json new file mode 100644 index 0000000..5690043 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-1.83/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-lcd-1.83", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-1.83/esp32-s3-touch-lcd-1.83.cc b/main/boards/waveshare-s3-touch-lcd-1.83/esp32-s3-touch-lcd-1.83.cc new file mode 100644 index 0000000..efcd631 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-1.83/esp32-s3-touch-lcd-1.83.cc @@ -0,0 +1,262 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "settings.h" + +#include +#include +#include + +#define TAG "WaveshareEsp32s3TouchLCD1inch83" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x01); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +class WaveshareEsp32s3TouchLCD1inch83 : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + Display* display_; + PowerSaveTimer* power_save_timer_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); }); + power_save_timer_->OnShutdownRequest([this](){ + pmic_->PowerOff(); }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_MOSI_PIN; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH* DISPLAY_HEIGHT* sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS_PIN; + io_config.dc_gpio_num = DISPLAY_DC_PIN; + io_config.spi_mode = 0; + io_config.pclk_hz = 24 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RST_PIN; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, true); + // esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + esp_lcd_panel_disp_on_off(panel, true); + display_ = new SpiLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeTouch() { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH - 1, + .y_max = DISPLAY_HEIGHT - 1, + .rst_gpio_num = GPIO_NUM_39, + .int_gpio_num = GPIO_NUM_13, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_CST816S_CONFIG(); + tp_io_config.scl_speed_hz = 400* 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_cst816s(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + // 初始化工具 + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + +public: + WaveshareEsp32s3TouchLCD1inch83() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeAxp2101(); + InitializeSpi(); + InitializeDisplay(); + InitializeTouch(); + InitializeButtons(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) + { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) + { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32s3TouchLCD1inch83); diff --git a/main/boards/waveshare-s3-touch-lcd-3.49/README.md b/main/boards/waveshare-s3-touch-lcd-3.49/README.md new file mode 100644 index 0000000..657331d --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.49/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-3.49 +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-3.49.htm \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.49/config.h b/main/boards/waveshare-s3-touch-lcd-3.49/config.h new file mode 100644 index 0000000..e2e9b79 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.49/config.h @@ -0,0 +1,62 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include +#include "lvgl.h" + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_7 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_46 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_45 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#define Dev_Touch_I2C_SDA_PIN GPIO_NUM_17 +#define Dev_Touch_I2C_SCL_PIN GPIO_NUM_18 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define I2C_Touch_ADDRESS 0x3b +#define I2C_Touch_SDA_PIN GPIO_NUM_17 +#define I2C_Touch_SCL_PIN GPIO_NUM_18 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define PWR_BUTTON_GPIO GPIO_NUM_16 + +#define LCD_CS GPIO_NUM_9 +#define LCD_PCLK GPIO_NUM_10 +#define LCD_D0 GPIO_NUM_11 +#define LCD_D1 GPIO_NUM_12 +#define LCD_D2 GPIO_NUM_13 +#define LCD_D3 GPIO_NUM_14 +#define LCD_RST GPIO_NUM_21 +#define LCD_LIGHT (-1) + +#define DISPLAY_WIDTH 172 +#define DISPLAY_HEIGHT 640 +#define LVGL_DMA_BUFF_LEN (DISPLAY_WIDTH * 64 * 2) +#define LVGL_SPIRAM_BUFF_LEN (DISPLAY_WIDTH * DISPLAY_HEIGHT * 2) + +#define DISPLAY_ROTATION_90 false + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_8 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-lcd-3.49/config.json b/main/boards/waveshare-s3-touch-lcd-3.49/config.json new file mode 100644 index 0000000..32de3cf --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.49/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-lcd-3.49", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.49/custom_lcd_display.cc b/main/boards/waveshare-s3-touch-lcd-3.49/custom_lcd_display.cc new file mode 100644 index 0000000..a5a466f --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.49/custom_lcd_display.cc @@ -0,0 +1,145 @@ +#include "custom_lcd_display.h" + +#include "lcd_display.h" + +#include +#include +#include +#include +#include "assets/lang_config.h" +#include +#include "settings.h" + +#include "esp_lcd_panel_io.h" + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "freertos/semphr.h" + +#include "config.h" + +#include "board.h" + +#define TAG "CustomLcdDisplay" + +static SemaphoreHandle_t trans_done_sem = NULL; +static uint16_t *trans_buf_1; + +#if (DISPLAY_ROTATION_90 == true) +static uint16_t *dest_map; +#endif + + +bool CustomLcdDisplay::lvgl_port_flush_io_ready_callback(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t *edata, void *user_ctx) { + BaseType_t taskAwake = pdFALSE; + lv_display_t *disp_drv = (lv_display_t *)user_ctx; + assert(disp_drv != NULL); + if (trans_done_sem) { + xSemaphoreGiveFromISR(trans_done_sem, &taskAwake); + } + return false; +} + +void CustomLcdDisplay::lvgl_port_flush_callback(lv_display_t *drv, const lv_area_t *area, uint8_t *color_map) { + assert(drv != NULL); + esp_lcd_panel_handle_t panel_handle = (esp_lcd_panel_handle_t)lv_display_get_user_data(drv); + assert(panel_handle != NULL); + + lv_draw_sw_rgb565_swap(color_map, lv_area_get_width(area) * lv_area_get_height(area)); + +#if (DISPLAY_ROTATION_90 == true) + lv_display_rotation_t rotation = lv_display_get_rotation(drv); + lv_area_t rotated_area; + if(rotation != LV_DISPLAY_ROTATION_0) { + lv_color_format_t cf = lv_display_get_color_format(drv); + /*Calculate the position of the rotated area*/ + rotated_area = *area; + lv_display_rotate_area(drv, &rotated_area); + /*Calculate the source stride (bytes in a line) from the width of the area*/ + uint32_t src_stride = lv_draw_buf_width_to_stride(lv_area_get_width(area), cf); + /*Calculate the stride of the destination (rotated) area too*/ + uint32_t dest_stride = lv_draw_buf_width_to_stride(lv_area_get_width(&rotated_area), cf); + /*Have a buffer to store the rotated area and perform the rotation*/ + + int32_t src_w = lv_area_get_width(area); + int32_t src_h = lv_area_get_height(area); + lv_draw_sw_rotate(color_map, dest_map, src_w, src_h, src_stride, dest_stride, rotation, cf); + /*Use the rotated area and rotated buffer from now on*/ + area = &rotated_area; + } +#endif + const int flush_coun = (LVGL_SPIRAM_BUFF_LEN / LVGL_DMA_BUFF_LEN); + const int offgap = (DISPLAY_HEIGHT / flush_coun); + const int dmalen = (LVGL_DMA_BUFF_LEN / 2); + int offsetx1 = 0; + int offsety1 = 0; + int offsetx2 = DISPLAY_WIDTH; + int offsety2 = offgap; +#if (DISPLAY_ROTATION_90 == true) + uint16_t *map = (uint16_t*)dest_map; +#else + uint16_t *map = (uint16_t*)color_map; +#endif + xSemaphoreGive(trans_done_sem); + + for(int i = 0; i +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include + +#include +#include "esp_io_expander_tca9554.h" + +#include "esp_lcd_axs15231b.h" + +#include "custom_lcd_display.h" + +#include + +#define TAG "waveshare_lcd_3_39" + + +static const axs15231b_lcd_init_cmd_t lcd_init_cmds[] = { + {0x11, (uint8_t []){0x00}, 0, 100}, + {0x29, (uint8_t []){0x00}, 0, 100}, +}; + +class CustomBoard : public WifiBoard { +private: + Button boot_button_; + Button pwr_button_; + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + i2c_master_dev_handle_t disp_touch_dev_handle = NULL; + lv_indev_t *touch_indev = NULL; //touch + bool is_PwrControlEn = false; + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_7 | IO_EXPANDER_PIN_NUM_6, IO_EXPANDER_OUTPUT); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_7 | IO_EXPANDER_PIN_NUM_6, 1); + ESP_ERROR_CHECK(ret); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.data0_io_num = LCD_D0; + buscfg.data1_io_num = LCD_D1; + buscfg.data2_io_num = LCD_D2; + buscfg.data3_io_num = LCD_D3; + buscfg.sclk_io_num = LCD_PCLK; + buscfg.max_transfer_sz = LVGL_DMA_BUFF_LEN; + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // RESET PIN INIT + gpio_config_t gpio_conf = {}; + gpio_conf.intr_type = GPIO_INTR_DISABLE; + gpio_conf.mode = GPIO_MODE_OUTPUT; + gpio_conf.pin_bit_mask = ((uint64_t)0x01<0 && buff[1]<5) { + indevData->state = LV_INDEV_STATE_PRESSED; + if(pointX > DISPLAY_WIDTH) pointX = DISPLAY_WIDTH; + if(pointY > DISPLAY_HEIGHT) pointY = DISPLAY_HEIGHT; + indevData->point.x = pointY; + indevData->point.y = (DISPLAY_HEIGHT-pointX); + ESP_LOGE("Touch","(%ld,%ld)",indevData->point.x,indevData->point.y); + } else { + indevData->state = LV_INDEV_STATE_RELEASED; + } + } + + void GetPwrCurrentState() { + if(gpio_get_level(PWR_BUTTON_GPIO)) { + is_PwrControlEn = true; + } + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO), + pwr_button_(PWR_BUTTON_GPIO) { + InitializeI2c(); + InitializeTca9554(); + InitializeSpi(); + InitializeLcdDisplay(); + InitializeButtons(); + InitializeTouch(); + GetPwrCurrentState(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } +}; + +DECLARE_BOARD(CustomBoard); \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/README.md b/main/boards/waveshare-s3-touch-lcd-3.5b/README.md new file mode 100644 index 0000000..aaadeae --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/README.md @@ -0,0 +1,3 @@ +新增 微雪 开发板: ESP32-S3-Touch-LCD-3.5B +产品链接: +https://www.waveshare.net/shop/ESP32-S3-Touch-LCD-3.5B.htm \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/config.h b/main/boards/waveshare-s3-touch-lcd-3.5b/config.h new file mode 100644 index 0000000..c44d734 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/config.h @@ -0,0 +1,78 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include +#include +#include "lvgl.h" + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_44 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_15 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_14 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_16 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_8 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_7 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_NC +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SPI_MODE 0 +#define DISPLAY_CS_PIN GPIO_NUM_12 +#define DISPLAY_CLK_PIN GPIO_NUM_5 +#define DISPLAY_DATA0_PIN GPIO_NUM_1 +#define DISPLAY_DATA1_PIN GPIO_NUM_2 +#define DISPLAY_DATA2_PIN GPIO_NUM_3 +#define DISPLAY_DATA3_PIN GPIO_NUM_4 + +#define DISPLAY_RST_PIN GPIO_NUM_NC + + + +#define DISPLAY_WIDTH 480 +#define DISPLAY_HEIGHT 320 +#define DISPLAY_TRANS_SIZE (DISPLAY_WIDTH * 10) + +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define DISPLAY_SWAP_XY false +#define DISPLAY_RGB_ORDER LCD_RGB_ELEMENT_ORDER_RGB +#define DISPLAY_INVERT_COLOR false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define LV_DISPLAY_ROTATION LV_DISPLAY_ROTATION_90 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_6 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define PMIC_ENABLE 0 +#define TOUCH_ENABLE 1 + +#define CAM_PIN_PWDN GPIO_NUM_NC +#define CAM_PIN_RESET GPIO_NUM_NC +#define CAM_PIN_VSYNC GPIO_NUM_17 +#define CAM_PIN_HREF GPIO_NUM_18 +#define CAM_PIN_PCLK GPIO_NUM_41 +#define CAM_PIN_XCLK GPIO_NUM_38 +#define CAM_PIN_SIOD GPIO_NUM_NC +#define CAM_PIN_SIOC GPIO_NUM_NC +#define CAM_PIN_D0 GPIO_NUM_45 +#define CAM_PIN_D1 GPIO_NUM_47 +#define CAM_PIN_D2 GPIO_NUM_48 +#define CAM_PIN_D3 GPIO_NUM_46 +#define CAM_PIN_D4 GPIO_NUM_42 +#define CAM_PIN_D5 GPIO_NUM_40 +#define CAM_PIN_D6 GPIO_NUM_39 +#define CAM_PIN_D7 GPIO_NUM_21 + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/config.json b/main/boards/waveshare-s3-touch-lcd-3.5b/config.json new file mode 100644 index 0000000..27c8e94 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/config.json @@ -0,0 +1,19 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-lcd-3.5b", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y", + "CONFIG_CAMERA_OV2640=y", + "CONFIG_CAMERA_OV2640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV2640_DVP_YUV422_640X480_6FPS=y", + "CONFIG_CAMERA_OV2640_DVP_IF_FORMAT_INDEX_DEFAULT=1", + "CONFIG_CAMERA_OV5640=y", + "CONFIG_CAMERA_OV5640_AUTO_DETECT_DVP_INTERFACE_SENSOR=y", + "CONFIG_CAMERA_OV5640_DVP_YUV422_800X600_10FPS=y", + "CONFIG_CAMERA_OV5640_DVP_IF_FORMAT_INDEX_DEFAULT=0" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.cc b/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.cc new file mode 100644 index 0000000..11d492f --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.cc @@ -0,0 +1,286 @@ + +#include "config.h" +#include "custom_lcd_display.h" +#include "lcd_display.h" +#include "assets/lang_config.h" +#include "settings.h" +#include "board.h" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "CustomLcdDisplay" + + +static SemaphoreHandle_t trans_done_sem = NULL; +static uint16_t *trans_act; +static uint16_t *trans_buf_1; +static uint16_t *trans_buf_2; + +bool CustomLcdDisplay::lvgl_port_flush_io_ready_callback(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t *edata, void *user_ctx) +{ + BaseType_t taskAwake = pdFALSE; + lv_display_t *disp_drv = (lv_display_t *)user_ctx; + assert(disp_drv != NULL); + if (trans_done_sem) { + xSemaphoreGiveFromISR(trans_done_sem, &taskAwake); + } + return false; +} + +void CustomLcdDisplay::lvgl_port_flush_callback(lv_display_t *drv, const lv_area_t *area, uint8_t *color_map) +{ + assert(drv != NULL); + esp_lcd_panel_handle_t panel_handle = (esp_lcd_panel_handle_t)lv_display_get_driver_data(drv); + assert(panel_handle != NULL); + + size_t len = lv_area_get_size(area); + lv_draw_sw_rgb565_swap(color_map, len); + + const int x_start = area->x1; + const int x_end = area->x2; + const int y_start = area->y1; + const int y_end = area->y2; + const int width = x_end - x_start + 1; + const int height = y_end - y_start + 1; + + int32_t hor_res = lv_display_get_horizontal_resolution(drv); + int32_t ver_res = lv_display_get_vertical_resolution(drv); + + // printf("hor_res: %ld, ver_res: %ld\r\n", hor_res, ver_res); + // printf("x_start: %d, x_end: %d, y_start: %d, y_end: %d, width: %d, height: %d\r\n", x_start, x_end, y_start, y_end, width, height); + uint16_t *from = (uint16_t *)color_map; + uint16_t *to = NULL; + + if (DISPLAY_TRANS_SIZE > 0) { + assert(trans_buf_1 != NULL); + + int x_draw_start = 0; + int x_draw_end = 0; + int y_draw_start = 0; + int y_draw_end = 0; + int trans_count = 0; + + trans_act = trans_buf_1; + lv_display_rotation_t rotate = LV_DISPLAY_ROTATION; + + int x_start_tmp = 0; + int x_end_tmp = 0; + int max_width = 0; + int trans_width = 0; + + int y_start_tmp = 0; + int y_end_tmp = 0; + int max_height = 0; + int trans_height = 0; + + if (LV_DISPLAY_ROTATION_270 == rotate || LV_DISPLAY_ROTATION_90 == rotate) { + max_width = ((DISPLAY_TRANS_SIZE / height) > width) ? (width) : (DISPLAY_TRANS_SIZE / height); + trans_count = width / max_width + (width % max_width ? (1) : (0)); + + x_start_tmp = x_start; + x_end_tmp = x_end; + } else { + max_height = ((DISPLAY_TRANS_SIZE / width) > height) ? (height) : (DISPLAY_TRANS_SIZE / width); + trans_count = height / max_height + (height % max_height ? (1) : (0)); + + y_start_tmp = y_start; + y_end_tmp = y_end; + } + + for (int i = 0; i < trans_count; i++) { + + if (LV_DISPLAY_ROTATION_90 == rotate) { + trans_width = (x_end - x_start_tmp + 1) > max_width ? max_width : (x_end - x_start_tmp + 1); + x_end_tmp = (x_end - x_start_tmp + 1) > max_width ? (x_start_tmp + max_width - 1) : x_end; + } else if (LV_DISPLAY_ROTATION_270 == rotate) { + trans_width = (x_end_tmp - x_start + 1) > max_width ? max_width : (x_end_tmp - x_start + 1); + x_start_tmp = (x_end_tmp - x_start + 1) > max_width ? (x_end_tmp - trans_width + 1) : x_start; + } else if (LV_DISPLAY_ROTATION_0 == rotate) { + trans_height = (y_end - y_start_tmp + 1) > max_height ? max_height : (y_end - y_start_tmp + 1); + y_end_tmp = (y_end - y_start_tmp + 1) > max_height ? (y_start_tmp + max_height - 1) : y_end; + } else { + trans_height = (y_end_tmp - y_start + 1) > max_height ? max_height : (y_end_tmp - y_start + 1); + y_start_tmp = (y_end_tmp - y_start + 1) > max_height ? (y_end_tmp - max_height + 1) : y_start; + } + + trans_act = (trans_act == trans_buf_1) ? (trans_buf_2) : (trans_buf_1); + to = trans_act; + + switch (rotate) { + case LV_DISPLAY_ROTATION_90: + for (int y = 0; y < height; y++) { + for (int x = 0; x < trans_width; x++) { + *(to + x * height + (height - y - 1)) = *(from + y * width + x_start_tmp + x); + } + } + x_draw_start = ver_res - y_end - 1; + x_draw_end = ver_res - y_start - 1; + y_draw_start = x_start_tmp; + y_draw_end = x_end_tmp; + break; + case LV_DISPLAY_ROTATION_270: + for (int y = 0; y < height; y++) { + for (int x = 0; x < trans_width; x++) { + *(to + (trans_width - x - 1) * height + y) = *(from + y * width + x_start_tmp + x); + } + } + x_draw_start = y_start; + x_draw_end = y_end; + y_draw_start = hor_res - x_end_tmp - 1; + y_draw_end = hor_res - x_start_tmp - 1; + break; + case LV_DISPLAY_ROTATION_180: + for (int y = 0; y < trans_height; y++) { + for (int x = 0; x < width; x++) { + *(to + (trans_height - y - 1)*width + (width - x - 1)) = *(from + y_start_tmp * width + y * (width) + x); + } + } + x_draw_start = hor_res - x_end - 1; + x_draw_end = hor_res - x_start - 1; + y_draw_start = ver_res - y_end_tmp - 1; + y_draw_end = ver_res - y_start_tmp - 1; + break; + case LV_DISPLAY_ROTATION_0: + for (int y = 0; y < trans_height; y++) { + for (int x = 0; x < width; x++) { + *(to + y * (width) + x) = *(from + y_start_tmp * width + y * (width) + x); + } + } + x_draw_start = x_start; + x_draw_end = x_end; + y_draw_start = y_start_tmp; + y_draw_end = y_end_tmp; + break; + default: + break; + } + + if (0 == i) { + // if (disp_ctx->draw_wait_cb) { + // disp_ctx->draw_wait_cb(disp_ctx->panel_handle->user_data); + // } + xSemaphoreGive(trans_done_sem); + } + + xSemaphoreTake(trans_done_sem, portMAX_DELAY); + // printf("i: %d, x_draw_start: %d, x_draw_end: %d, y_draw_start: %d, y_draw_end: %d\r\n", i, x_draw_start, x_draw_end, y_draw_start, y_draw_end); + esp_lcd_panel_draw_bitmap(panel_handle, x_draw_start, y_draw_start, x_draw_end + 1, y_draw_end + 1, to); + + if (LV_DISPLAY_ROTATION_90 == rotate) { + x_start_tmp += max_width; + } else if (LV_DISPLAY_ROTATION_270 == rotate) { + x_end_tmp -= max_width; + } if (LV_DISPLAY_ROTATION_0 == rotate) { + y_start_tmp += max_height; + } else { + y_end_tmp -= max_height; + } + } + } else { + esp_lcd_panel_draw_bitmap(panel_handle, x_start, y_start, x_end + 1, y_end + 1, color_map); + } + lv_disp_flush_ready(drv); +} + +CustomLcdDisplay::CustomLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : LcdDisplay(panel_io, panel, width, height) { + // width_ = width; + // height_ = height; + + // draw white + std::vector buffer(width_, 0xFFFF); + for (int y = 0; y < height_; y++) { + esp_lcd_panel_draw_bitmap(panel_, 0, y, width_, y + 1, buffer.data()); + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + ESP_LOGI(TAG, "Initialize LVGL library"); + lv_init(); + + ESP_LOGI(TAG, "Initialize LVGL port"); + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + port_cfg.task_priority = 1; + port_cfg.timer_period_ms = 50; + lvgl_port_init(&port_cfg); + trans_done_sem = xSemaphoreCreateCounting(1, 0); + trans_buf_1 = (uint16_t *)heap_caps_malloc(DISPLAY_TRANS_SIZE * sizeof(uint16_t), MALLOC_CAP_DMA); + trans_buf_2 = (uint16_t *)heap_caps_malloc(DISPLAY_TRANS_SIZE * sizeof(uint16_t), MALLOC_CAP_DMA); +#if 0 + ESP_LOGI(TAG, "Adding LCD screen"); + const lvgl_port_display_cfg_t display_cfg = { + .io_handle = panel_io_, + .panel_handle = panel_, + .control_handle = nullptr, + .buffer_size = static_cast(width_ * height_), + .double_buffer = false, + .trans_size = 0, + .hres = static_cast(width_), + .vres = static_cast(height_), + .monochrome = false, + .rotation = { + .swap_xy = swap_xy, + .mirror_x = mirror_x, + .mirror_y = mirror_y, + }, + .color_format = LV_COLOR_FORMAT_RGB565, + .flags = { + .buff_dma = 0, + .buff_spiram = 1, + .sw_rotate = 0, + .swap_bytes = 1, + .full_refresh = 1, + .direct_mode = 0, + }, + }; + + display_ = lvgl_port_add_disp(&display_cfg); + lv_display_set_flush_cb(display_, lvgl_port_flush_callback); +#else + + uint32_t buffer_size = 0; + lv_color_t *buf1 = NULL; + lvgl_port_lock(0); + uint8_t color_bytes = lv_color_format_get_size(LV_COLOR_FORMAT_RGB565); + display_ = lv_display_create(width_, height_); + lv_display_set_flush_cb(display_, lvgl_port_flush_callback); + buffer_size = width_ * height_; + buf1 = (lv_color_t *)heap_caps_aligned_alloc(1, buffer_size * color_bytes, MALLOC_CAP_SPIRAM); + lv_display_set_buffers(display_, buf1, NULL, buffer_size * color_bytes, LV_DISPLAY_RENDER_MODE_FULL); + lv_display_set_driver_data(display_, panel_); + lvgl_port_unlock(); + +#endif + + esp_lcd_panel_io_callbacks_t cbs = { + .on_color_trans_done = lvgl_port_flush_io_ready_callback, + }; + /* Register done callback */ + esp_lcd_panel_io_register_event_callbacks(panel_io_, &cbs, display_); + + esp_lcd_panel_disp_on_off(panel_, false); + + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add display"); + return; + } + + if (offset_x != 0 || offset_y != 0) { + lv_display_set_offset(display_, offset_x, offset_y); + } + + + SetupUI(); +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.h b/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.h new file mode 100644 index 0000000..c3a9900 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/custom_lcd_display.h @@ -0,0 +1,19 @@ +#ifndef __CUSTOM_LCD_DISPLAY_H__ +#define __CUSTOM_LCD_DISPLAY_H__ + +#include "lcd_display.h" + +// // SPI LCD显示器 +class CustomLcdDisplay : public LcdDisplay { +public: + CustomLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy); +private: + static bool lvgl_port_flush_io_ready_callback(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t *edata, void *user_ctx); + static void lvgl_port_flush_callback(lv_display_t *drv, const lv_area_t *area, uint8_t *color_map); +}; + + + +#endif // __CUSTOM_LCD_DISPLAY_H__ \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-3.5b/waveshare-s3-touch-lcd-3.5b.cc b/main/boards/waveshare-s3-touch-lcd-3.5b/waveshare-s3-touch-lcd-3.5b.cc new file mode 100644 index 0000000..2b89f94 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-3.5b/waveshare-s3-touch-lcd-3.5b.cc @@ -0,0 +1,365 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" + +#include +#include "i2c_device.h" +#include +#include +#include +#include +#include +#include + +#include +#include "esp_io_expander_tca9554.h" + +#include "axp2101.h" +#include "power_save_timer.h" + +#include "esp_lcd_axs15231b.h" + +#include "custom_lcd_display.h" + +#include + +#include +#include +#include "esp32_camera.h" + +#define TAG "waveshare_lcd_3_5b" + +static const axs15231b_lcd_init_cmd_t lcd_init_cmds[] = { + {0xBB, (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5A, 0xA5}, 8, 0}, + {0xA0, (uint8_t[]){0xC0, 0x10, 0x00, 0x02, 0x00, 0x00, 0x04, 0x3F, 0x20, 0x05, 0x3F, 0x3F, 0x00, 0x00, 0x00, 0x00, 0x00}, 17, 0}, + {0xA2, (uint8_t[]){0x30, 0x3C, 0x24, 0x14, 0xD0, 0x20, 0xFF, 0xE0, 0x40, 0x19, 0x80, 0x80, 0x80, 0x20, 0xf9, 0x10, 0x02, 0xff, 0xff, 0xF0, 0x90, 0x01, 0x32, 0xA0, 0x91, 0xE0, 0x20, 0x7F, 0xFF, 0x00, 0x5A}, 31, 0}, + {0xD0, (uint8_t[]){0xE0, 0x40, 0x51, 0x24, 0x08, 0x05, 0x10, 0x01, 0x20, 0x15, 0x42, 0xC2, 0x22, 0x22, 0xAA, 0x03, 0x10, 0x12, 0x60, 0x14, 0x1E, 0x51, 0x15, 0x00, 0x8A, 0x20, 0x00, 0x03, 0x3A, 0x12}, 30, 0}, + {0xA3, (uint8_t[]){0xA0, 0x06, 0xAa, 0x00, 0x08, 0x02, 0x0A, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x00, 0x55, 0x55}, 22, 0}, + {0xC1, (uint8_t[]){0x31, 0x04, 0x02, 0x02, 0x71, 0x05, 0x24, 0x55, 0x02, 0x00, 0x41, 0x00, 0x53, 0xFF, 0xFF, 0xFF, 0x4F, 0x52, 0x00, 0x4F, 0x52, 0x00, 0x45, 0x3B, 0x0B, 0x02, 0x0d, 0x00, 0xFF, 0x40}, 30, 0}, + {0xC3, (uint8_t[]){0x00, 0x00, 0x00, 0x50, 0x03, 0x00, 0x00, 0x00, 0x01, 0x80, 0x01}, 11, 0}, + {0xC4, (uint8_t[]){0x00, 0x24, 0x33, 0x80, 0x00, 0xea, 0x64, 0x32, 0xC8, 0x64, 0xC8, 0x32, 0x90, 0x90, 0x11, 0x06, 0xDC, 0xFA, 0x00, 0x00, 0x80, 0xFE, 0x10, 0x10, 0x00, 0x0A, 0x0A, 0x44, 0x50}, 29, 0}, + {0xC5, (uint8_t[]){0x18, 0x00, 0x00, 0x03, 0xFE, 0x3A, 0x4A, 0x20, 0x30, 0x10, 0x88, 0xDE, 0x0D, 0x08, 0x0F, 0x0F, 0x01, 0x3A, 0x4A, 0x20, 0x10, 0x10, 0x00}, 23, 0}, + {0xC6, (uint8_t[]){0x05, 0x0A, 0x05, 0x0A, 0x00, 0xE0, 0x2E, 0x0B, 0x12, 0x22, 0x12, 0x22, 0x01, 0x03, 0x00, 0x3F, 0x6A, 0x18, 0xC8, 0x22}, 20, 0}, + {0xC7, (uint8_t[]){0x50, 0x32, 0x28, 0x00, 0xa2, 0x80, 0x8f, 0x00, 0x80, 0xff, 0x07, 0x11, 0x9c, 0x67, 0xff, 0x24, 0x0c, 0x0d, 0x0e, 0x0f}, 20, 0}, + {0xC9, (uint8_t[]){0x33, 0x44, 0x44, 0x01}, 4, 0}, + {0xCF, (uint8_t[]){0x2C, 0x1E, 0x88, 0x58, 0x13, 0x18, 0x56, 0x18, 0x1E, 0x68, 0x88, 0x00, 0x65, 0x09, 0x22, 0xC4, 0x0C, 0x77, 0x22, 0x44, 0xAA, 0x55, 0x08, 0x08, 0x12, 0xA0, 0x08}, 27, 0}, + {0xD5, (uint8_t[]){0x40, 0x8E, 0x8D, 0x01, 0x35, 0x04, 0x92, 0x74, 0x04, 0x92, 0x74, 0x04, 0x08, 0x6A, 0x04, 0x46, 0x03, 0x03, 0x03, 0x03, 0x82, 0x01, 0x03, 0x00, 0xE0, 0x51, 0xA1, 0x00, 0x00, 0x00}, 30, 0}, + {0xD6, (uint8_t[]){0x10, 0x32, 0x54, 0x76, 0x98, 0xBA, 0xDC, 0xFE, 0x93, 0x00, 0x01, 0x83, 0x07, 0x07, 0x00, 0x07, 0x07, 0x00, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x00, 0x84, 0x00, 0x20, 0x01, 0x00}, 30, 0}, + {0xD7, (uint8_t[]){0x03, 0x01, 0x0b, 0x09, 0x0f, 0x0d, 0x1E, 0x1F, 0x18, 0x1d, 0x1f, 0x19, 0x40, 0x8E, 0x04, 0x00, 0x20, 0xA0, 0x1F}, 19, 0}, + {0xD8, (uint8_t[]){0x02, 0x00, 0x0a, 0x08, 0x0e, 0x0c, 0x1E, 0x1F, 0x18, 0x1d, 0x1f, 0x19}, 12, 0}, + {0xD9, (uint8_t[]){0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F}, 12, 0}, + {0xDD, (uint8_t[]){0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F}, 12, 0}, + {0xDF, (uint8_t[]){0x44, 0x73, 0x4B, 0x69, 0x00, 0x0A, 0x02, 0x90}, 8, 0}, + {0xE0, (uint8_t[]){0x3B, 0x28, 0x10, 0x16, 0x0c, 0x06, 0x11, 0x28, 0x5c, 0x21, 0x0D, 0x35, 0x13, 0x2C, 0x33, 0x28, 0x0D}, 17, 0}, + {0xE1, (uint8_t[]){0x37, 0x28, 0x10, 0x16, 0x0b, 0x06, 0x11, 0x28, 0x5C, 0x21, 0x0D, 0x35, 0x14, 0x2C, 0x33, 0x28, 0x0F}, 17, 0}, + {0xE2, (uint8_t[]){0x3B, 0x07, 0x12, 0x18, 0x0E, 0x0D, 0x17, 0x35, 0x44, 0x32, 0x0C, 0x14, 0x14, 0x36, 0x3A, 0x2F, 0x0D}, 17, 0}, + {0xE3, (uint8_t[]){0x37, 0x07, 0x12, 0x18, 0x0E, 0x0D, 0x17, 0x35, 0x44, 0x32, 0x0C, 0x14, 0x14, 0x36, 0x32, 0x2F, 0x0F}, 17, 0}, + {0xE4, (uint8_t[]){0x3B, 0x07, 0x12, 0x18, 0x0E, 0x0D, 0x17, 0x39, 0x44, 0x2E, 0x0C, 0x14, 0x14, 0x36, 0x3A, 0x2F, 0x0D}, 17, 0}, + {0xE5, (uint8_t[]){0x37, 0x07, 0x12, 0x18, 0x0E, 0x0D, 0x17, 0x39, 0x44, 0x2E, 0x0C, 0x14, 0x14, 0x36, 0x3A, 0x2F, 0x0F}, 17, 0}, + {0xA4, (uint8_t[]){0x85, 0x85, 0x95, 0x82, 0xAF, 0xAA, 0xAA, 0x80, 0x10, 0x30, 0x40, 0x40, 0x20, 0xFF, 0x60, 0x30}, 16, 0}, + {0xA4, (uint8_t[]){0x85, 0x85, 0x95, 0x85}, 4, 0}, + {0xBB, (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, 8, 0}, + {0x13, (uint8_t[]){0x00}, 0, 0}, + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0x2C, (uint8_t[]){0x00, 0x00, 0x00, 0x00}, 4, 0}, + {0x2a, (uint8_t[]){0x00, 0x00, 0x01, 0x3f}, 4, 0}, + {0x2b, (uint8_t[]){0x00, 0x00, 0x01, 0xdf}, 4, 0}}; + +class Pmic : public Axp2101 { + public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + WriteReg(0x96, (1500 - 500) / 100); + WriteReg(0x97, (2800 - 500) / 100); + + // Enable ALDO1 BLDO1 BLDO2 + WriteReg(0x90, 0x31); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } + }; + +class CustomBoard : public WifiBoard { +private: + Button boot_button_; + Pmic* pmic_ = nullptr; + i2c_master_bus_handle_t i2c_bus_; + esp_io_expander_handle_t io_expander = NULL; + LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + Esp32Camera* camera_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(20); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + pmic_->PowerOff(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = (i2c_port_t)I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) + { + esp_err_t ret = esp_io_expander_new_i2c_tca9554(i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000, &io_expander); + if(ret != ESP_OK) + ESP_LOGE(TAG, "TCA9554 create returned error"); + ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, IO_EXPANDER_OUTPUT); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_0 | IO_EXPANDER_PIN_NUM_1, 0); + ESP_ERROR_CHECK(ret); + vTaskDelay(pdMS_TO_TICKS(100)); + ret = esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_1, 1); + ESP_ERROR_CHECK(ret); + } + + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeSpi() { + ESP_LOGI(TAG, "Initialize QSPI bus"); + spi_bus_config_t buscfg = {}; + buscfg.data0_io_num = DISPLAY_DATA0_PIN; + buscfg.data1_io_num = DISPLAY_DATA1_PIN; + buscfg.data2_io_num = DISPLAY_DATA2_PIN; + buscfg.data3_io_num = DISPLAY_DATA3_PIN; + buscfg.sclk_io_num = DISPLAY_CLK_PIN; + buscfg.max_transfer_sz = DISPLAY_TRANS_SIZE * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI2_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeCamera() { + static esp_cam_ctlr_dvp_pin_config_t dvp_pin_config = { + .data_width = CAM_CTLR_DATA_WIDTH_8, + .data_io = { + [0] = CAM_PIN_D0, + [1] = CAM_PIN_D1, + [2] = CAM_PIN_D2, + [3] = CAM_PIN_D3, + [4] = CAM_PIN_D4, + [5] = CAM_PIN_D5, + [6] = CAM_PIN_D6, + [7] = CAM_PIN_D7, + }, + .vsync_io = CAM_PIN_VSYNC, + .de_io = CAM_PIN_HREF, + .pclk_io = CAM_PIN_PCLK, + .xclk_io = CAM_PIN_XCLK, + }; + + esp_video_init_sccb_config_t sccb_config = { + .init_sccb = false, // 不初始化新的 SCCB,使用现有的 I2C 总线 + .i2c_handle = i2c_bus_, // 使用现有的 I2C 总线句柄 + .freq = 100000, // 100kHz + }; + + esp_video_init_dvp_config_t dvp_config = { + .sccb_config = sccb_config, + .reset_pin = CAM_PIN_RESET, + .pwdn_pin = CAM_PIN_PWDN, + .dvp_pin = dvp_pin_config, + .xclk_freq = 12000000, + }; + + esp_video_init_config_t video_config = { + .dvp = &dvp_config, + }; + + camera_ = new Esp32Camera(video_config); + + } + + void InitializeLcdDisplay() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGI(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = AXS15231B_PANEL_IO_QSPI_CONFIG( + DISPLAY_CS_PIN, + NULL, + NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI2_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片 + ESP_LOGI(TAG, "Install LCD driver"); + const axs15231b_vendor_config_t vendor_config = { + .init_cmds = lcd_init_cmds, // Uncomment these line if use custom initialization commands + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]), + .flags = { + .use_qspi_interface = 1, + }, + }; + esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = DISPLAY_RST_PIN, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .vendor_config = (void *)&vendor_config, + }; + esp_lcd_new_panel_axs15231b(panel_io, &panel_config, &panel); + + esp_lcd_panel_reset(panel); + + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + // esp_lcd_panel_disp_on_off(panel, false); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + + display_ = new CustomLcdDisplay(panel_io, panel, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 1, + .mirror_x = 1, + .mirror_y = 1, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_AXS15231B_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_axs15231b(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + +public: + CustomBoard() : + boot_button_(BOOT_BUTTON_GPIO) { + + InitializeI2c(); + InitializeTca9554(); + + InitializeAxp2101(); +#if PMIC_ENABLE + InitializePowerSaveTimer(); +#endif + InitializeSpi(); + InitializeLcdDisplay(); +#if TOUCH_ENABLE + InitializeTouch(); +#endif + InitializeButtons(); + InitializeCamera(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + virtual Camera* GetCamera() override { + return camera_; + } + +#if PMIC_ENABLE + virtual bool GetBatteryLevel(int &level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +#endif +}; + +DECLARE_BOARD(CustomBoard); diff --git a/main/boards/waveshare-s3-touch-lcd-4b/README.md b/main/boards/waveshare-s3-touch-lcd-4b/README.md new file mode 100644 index 0000000..81dc450 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-4b/README.md @@ -0,0 +1,12 @@ +# Waveshare ESP32-S3-Touch-LCD-4B + + +[ESP32-S3-Touch-LCD-4B](https://www.waveshare.com/esp32-s3-touch-lcd-4b.htm) is waveshare electronics designed an intelligent 86 box based on ESP32-S3 module equipped with a 480*480 IPS capacitive touch screen + + +## Configuration + +Configuration in `menuconfig`. + +Selection Board Type `Xiaozhi Assistant --> Board Type` +- Waveshare ESP32-S3-Touch-LCD-4B \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-4b/config.h b/main/boards/waveshare-s3-touch-lcd-4b/config.h new file mode 100644 index 0000000..aba2eac --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-4b/config.h @@ -0,0 +1,65 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_7 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_16 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_15 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_6 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_NC +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_47 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_48 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR +#define AUDIO_CODEC_ES7210_ADDR ES7210_CODEC_DEFAULT_ADDR + +#define I2C_ADDRESS ESP_IO_EXPANDER_I2C_TCA9554_ADDRESS_000 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +#define BSP_LCD_VSYNC (GPIO_NUM_3) +#define BSP_LCD_HSYNC (GPIO_NUM_46) +#define BSP_LCD_DE (GPIO_NUM_17) +#define BSP_LCD_PCLK (GPIO_NUM_9) +#define BSP_LCD_DISP (GPIO_NUM_NC) +#define BSP_LCD_DATA0 (GPIO_NUM_40) +#define BSP_LCD_DATA1 (GPIO_NUM_41) +#define BSP_LCD_DATA2 (GPIO_NUM_42) +#define BSP_LCD_DATA3 (GPIO_NUM_2) +#define BSP_LCD_DATA4 (GPIO_NUM_1) +#define BSP_LCD_DATA5 (GPIO_NUM_21) +#define BSP_LCD_DATA6 (GPIO_NUM_8) +#define BSP_LCD_DATA7 (GPIO_NUM_18) +#define BSP_LCD_DATA8 (GPIO_NUM_45) +#define BSP_LCD_DATA9 (GPIO_NUM_38) +#define BSP_LCD_DATA10 (GPIO_NUM_39) +#define BSP_LCD_DATA11 (GPIO_NUM_10) +#define BSP_LCD_DATA12 (GPIO_NUM_11) +#define BSP_LCD_DATA13 (GPIO_NUM_12) +#define BSP_LCD_DATA14 (GPIO_NUM_13) +#define BSP_LCD_DATA15 (GPIO_NUM_14) + +#define BSP_LCD_IO_SPI_CS (IO_EXPANDER_PIN_NUM_0) +#define BSP_LCD_IO_SPI_SCL (IO_EXPANDER_PIN_NUM_2) +#define BSP_LCD_IO_SPI_SDA (IO_EXPANDER_PIN_NUM_1) + +#define DISPLAY_WIDTH 480 +#define DISPLAY_HEIGHT 480 + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_4 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/waveshare-s3-touch-lcd-4b/config.json b/main/boards/waveshare-s3-touch-lcd-4b/config.json new file mode 100644 index 0000000..f703cc0 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-4b/config.json @@ -0,0 +1,12 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "waveshare-s3-touch-lcd-4b", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/waveshare-s3-touch-lcd-4b/esp32-s3-touch-lcd-4b.cc b/main/boards/waveshare-s3-touch-lcd-4b/esp32-s3-touch-lcd-4b.cc new file mode 100644 index 0000000..bef2b55 --- /dev/null +++ b/main/boards/waveshare-s3-touch-lcd-4b/esp32-s3-touch-lcd-4b.cc @@ -0,0 +1,432 @@ +#include "wifi_board.h" +#include "display/lcd_display.h" +#include "esp_lcd_st7701.h" + +#include "codecs/box_audio_codec.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "config.h" +#include "power_save_timer.h" +#include "axp2101.h" +#include "i2c_device.h" +#include + +#include +#include +#include +#include +#include "esp_io_expander_tca9554.h" +#include "settings.h" + +#include +#include +#include + +#include +#include +#include +#include + +#define TAG "WaveshareEsp32s3TouchLCD4b" + +class Pmic : public Axp2101 { +public: + Pmic(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : Axp2101(i2c_bus, addr) { + WriteReg(0x22, 0b110); // PWRON > OFFLEVEL as POWEROFF Source enable + WriteReg(0x27, 0x10); // hold 4s to power off + + // Disable All DCs but DC1 + WriteReg(0x80, 0x01); + // Disable All LDOs + WriteReg(0x90, 0x00); + WriteReg(0x91, 0x00); + + // Set DC1 to 3.3V + WriteReg(0x82, (3300 - 1500) / 100); + + // Set ALDO1 to 3.3V + WriteReg(0x92, (3300 - 500) / 100); + + // Enable ALDO1(MIC) + WriteReg(0x90, 0x01); + + WriteReg(0x64, 0x02); // CV charger voltage setting to 4.1V + + WriteReg(0x61, 0x02); // set Main battery precharge current to 50mA + WriteReg(0x62, 0x08); // set Main battery charger current to 400mA ( 0x08-200mA, 0x09-300mA, 0x0A-400mA ) + WriteReg(0x63, 0x01); // set Main battery term charge current to 25mA + } +}; + +#define LCD_OPCODE_WRITE_CMD (0x02ULL) +#define LCD_OPCODE_READ_CMD (0x03ULL) +#define LCD_OPCODE_WRITE_COLOR (0x32ULL) + +static const st7701_lcd_init_cmd_t lcd_init_cmds[] = { +// {cmd, { data }, data_size, delay_ms} + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0xFF, (uint8_t[]){0x77, 0x01, 0x00, 0x00, 0x10}, 5, 0}, + {0xC0, (uint8_t[]){0x3B, 0x00}, 2, 0}, + {0xC1, (uint8_t[]){0x0D, 0x02}, 2, 0}, + {0xC2, (uint8_t[]){0x21, 0x08}, 2, 0}, + {0xCD, (uint8_t[]){0x08}, 1, 0}, + {0xB0, (uint8_t[]){0x00, 0x11, 0x18, 0x0E, 0x11, 0x06, 0x07, 0x08, 0x07, 0x22, 0x04, 0x12, 0x0F, 0xAA, 0x31, 0x18}, 16, 0}, + {0xB1, (uint8_t[]){0x00, 0x11, 0x19, 0x0E, 0x12, 0x07, 0x08, 0x08, 0x08, 0x22, 0x04, 0x11, 0x11, 0xA9, 0x32, 0x18}, 16, 0}, + {0xFF, (uint8_t[]){0x77, 0x01, 0x00, 0x00, 0x11}, 5, 0}, + {0xB0, (uint8_t[]){0x60}, 1, 0}, + {0xB1, (uint8_t[]){0x30}, 1, 0}, + {0xB2, (uint8_t[]){0x87}, 1, 0}, + {0xB3, (uint8_t[]){0x80}, 1, 0}, + {0xB5, (uint8_t[]){0x49}, 1, 0}, + {0xB7, (uint8_t[]){0x85}, 1, 0}, + {0xB8, (uint8_t[]){0x21}, 1, 0}, + {0xC1, (uint8_t[]){0x78}, 1, 0}, + {0xC2, (uint8_t[]){0x78}, 1, 20}, + {0xE0, (uint8_t[]){0x00, 0x1B, 0x02}, 3, 0}, + {0xE1, (uint8_t[]){0x08, 0xA0, 0x00, 0x00, 0x07, 0xA0, 0x00, 0x00, 0x00, 0x44, 0x44}, 11, 0}, + {0xE2, (uint8_t[]){0x11, 0x11, 0x44, 0x44, 0xED, 0xA0, 0x00, 0x00, 0xEC, 0xA0, 0x00, 0x00}, 12, 0}, + {0xE3, (uint8_t[]){0x00, 0x00, 0x11, 0x11}, 4, 0}, + {0xE4, (uint8_t[]){0x44, 0x44}, 2, 0}, + {0xE5, (uint8_t[]){0x0A, 0xE9, 0xD8, 0xA0, 0x0C, 0xEB, 0xD8, 0xA0, 0x0E, 0xED, 0xD8, 0xA0, 0x10, 0xEF, 0xD8, 0xA0}, 16, 0}, + {0xE6, (uint8_t[]){0x00, 0x00, 0x11, 0x11}, 4, 0}, + {0xE7, (uint8_t[]){0x44, 0x44}, 2, 0}, + {0xE8, (uint8_t[]){0x09, 0xE8, 0xD8, 0xA0, 0x0B, 0xEA, 0xD8, 0xA0, 0x0D, 0xEC, 0xD8, 0xA0, 0x0F, 0xEE, 0xD8, 0xA0}, 16, 0}, + {0xEB, (uint8_t[]){0x02, 0x00, 0xE4, 0xE4, 0x88, 0x00, 0x40}, 7, 0}, + {0xEC, (uint8_t[]){0x3C, 0x00}, 2, 0}, + {0xED, (uint8_t[]){0xAB, 0x89, 0x76, 0x54, 0x02, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x20, 0x45, 0x67, 0x98, 0xBA}, 16, 0}, + {0xFF, (uint8_t[]){0x77, 0x01, 0x00, 0x00, 0x00}, 5, 0}, + {0x36, (uint8_t[]){0x00}, 1, 0}, + {0x3A, (uint8_t[]){0x66}, 1, 0}, + {0x21, (uint8_t[]){0x00}, 0, 120}, + {0x29, (uint8_t[]){0x00}, 0, 0}, +}; + +class WaveshareEsp32s3TouchLCD4b : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Pmic* pmic_ = nullptr; + Button boot_button_; + LcdDisplay* display_; + esp_io_expander_handle_t io_expander = NULL; + PowerSaveTimer* power_save_timer_; + + uint32_t key_press_start; + bool key_pressed; + bool key_handled; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(70); }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); }); + power_save_timer_->OnShutdownRequest([this](){ + pmic_->PowerOff(); }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + void InitializeTca9554(void) { + esp_io_expander_new_i2c_tca9554(i2c_bus_, I2C_ADDRESS, &io_expander); + esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_3|IO_EXPANDER_PIN_NUM_5 | IO_EXPANDER_PIN_NUM_6 , IO_EXPANDER_OUTPUT); + esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_3, 1); + esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_6, 0); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_5, 0); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_io_expander_set_level(io_expander, IO_EXPANDER_PIN_NUM_5, 1); + vTaskDelay(pdMS_TO_TICKS(200)); + esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_4|IO_EXPANDER_PIN_NUM_6, IO_EXPANDER_INPUT); + } + void InitializeAxp2101() { + ESP_LOGI(TAG, "Init AXP2101"); + pmic_ = new Pmic(i2c_bus_, 0x34); + } + + void InitializeRGB() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + + spi_line_config_t line_config = { + .cs_io_type = IO_TYPE_EXPANDER, + .cs_expander_pin = BSP_LCD_IO_SPI_CS, + .scl_io_type = IO_TYPE_EXPANDER, + .scl_expander_pin = BSP_LCD_IO_SPI_SCL, + .sda_io_type = IO_TYPE_EXPANDER, + .sda_expander_pin = BSP_LCD_IO_SPI_SDA, + .io_expander = io_expander, + }; + esp_lcd_panel_io_3wire_spi_config_t io_config = ST7701_PANEL_IO_3WIRE_SPI_CONFIG(line_config, 0); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_3wire_spi(&io_config, &panel_io)); + esp_lcd_panel_handle_t panel_handle = NULL; + esp_lcd_rgb_panel_config_t rgb_config = { + .clk_src = LCD_CLK_SRC_DEFAULT, + .timings = { + .pclk_hz = 16 * 1000 * 1000, + .h_res = DISPLAY_WIDTH, + .v_res = DISPLAY_HEIGHT, + .hsync_pulse_width = 10, + .hsync_back_porch = 10, + .hsync_front_porch = 20, + .vsync_pulse_width = 10, + .vsync_back_porch = 10, + .vsync_front_porch = 10, + .flags = { + .pclk_active_neg = false + } + }, + .data_width = 16, + .bits_per_pixel = 16, + .num_fbs = 2, + .bounce_buffer_size_px = 480 * 20, + .psram_trans_align = 64, + .hsync_gpio_num = BSP_LCD_HSYNC, + .vsync_gpio_num = BSP_LCD_VSYNC, + .de_gpio_num = BSP_LCD_DE, + .pclk_gpio_num = BSP_LCD_PCLK, + .disp_gpio_num = BSP_LCD_DISP, + .data_gpio_nums = { + BSP_LCD_DATA0, BSP_LCD_DATA1, BSP_LCD_DATA2, BSP_LCD_DATA3, + BSP_LCD_DATA4, BSP_LCD_DATA5, BSP_LCD_DATA6, BSP_LCD_DATA7, + BSP_LCD_DATA8, BSP_LCD_DATA9, BSP_LCD_DATA10, BSP_LCD_DATA11, + BSP_LCD_DATA12, BSP_LCD_DATA13, BSP_LCD_DATA14, BSP_LCD_DATA15 + }, + .flags = { + .fb_in_psram = 1, + }, + }; + + rgb_config.timings.h_res = DISPLAY_WIDTH; + rgb_config.timings.v_res = DISPLAY_HEIGHT; + st7701_vendor_config_t vendor_config = { + .init_cmds = lcd_init_cmds, + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(lcd_init_cmds[0]), + .rgb_config = &rgb_config, + .flags = { + .mirror_by_cmd = 0, + .auto_del_panel_io = 1, + } + }; + const esp_lcd_panel_dev_config_t panel_config = { + .reset_gpio_num = GPIO_NUM_NC, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 18, + .vendor_config = &vendor_config, + }; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7701(panel_io, &panel_config, &panel_handle)); + esp_lcd_panel_init(panel_handle); + + display_ = new RgbLcdDisplay(panel_io, panel_handle, + DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + +#if CONFIG_USE_DEVICE_AEC + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + app.SetAecMode(app.GetAecMode() == kAecOff ? kAecOnDeviceSide : kAecOff); + } + }); +#endif + } + + void InitializeTouch() { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH - 1, + .y_max = DISPLAY_HEIGHT - 1, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_NC, + .levels = { + .reset = 0, + .interrupt = 0, + }, + .flags = { + .swap_xy = 0, + .mirror_x = 0, + .mirror_y = 0, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.scl_speed_hz = 400* 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + void InitializeTools() { + auto &mcp_server = McpServer::GetInstance(); + mcp_server.AddTool("self.system.reconfigure_wifi", + "Reboot the device and enter WiFi configuration mode.\n" + "**CAUTION** You must ask the user to confirm this action.", + PropertyList(), [this](const PropertyList& properties) { + ResetWifiConfiguration(); + return true; + }); + } + void CheckKeyState() { + if (!io_expander) return; + + uint32_t current_level; + esp_err_t ret = esp_io_expander_get_level(io_expander, IO_EXPANDER_PIN_NUM_4, ¤t_level); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to read IO_EXPANDER_PIN_NUM_4 level"); + return; + } + + static uint32_t last_level = 0; + static uint64_t press_start_time_ms = 0; + + if (current_level != last_level) { + last_level = current_level; + + if (current_level > 0) { + press_start_time_ms = esp_timer_get_time() / 1000; + ESP_LOGD(TAG, "Button pressed, start time recorded"); + } else { + uint64_t press_duration = (esp_timer_get_time() / 1000) - press_start_time_ms; + ESP_LOGI(TAG, "Button released after %llums", press_duration); + + if (press_duration < 1000) { + ESP_LOGI(TAG, "Short press detected, switching to factory partition"); + + const esp_partition_t* factory_partition = esp_partition_find_first( + ESP_PARTITION_TYPE_APP, + ESP_PARTITION_SUBTYPE_APP_FACTORY, + nullptr + ); + if (factory_partition) { + ESP_LOGI(TAG, "Found factory partition: %s", factory_partition->label); + ESP_ERROR_CHECK(esp_ota_set_boot_partition(factory_partition)); + esp_restart(); + } else { + ESP_LOGE(TAG, "Factory partition not found"); + } + } else { + ESP_LOGI(TAG, "Long press detected (>1000ms), no action"); + } + } + } + } + + void InitializeKeyMonitor() { + key_press_start = 0; + key_pressed = false; + key_handled = false; + + xTaskCreatePinnedToCore( + [](void* arg) { + auto* board = static_cast(arg); + while (true) { + board->CheckKeyState(); + vTaskDelay(pdMS_TO_TICKS(20)); + } + }, + "key_monitor_task", + 4096, + this, + 5, + nullptr, + 0 + ); + } + +public: + WaveshareEsp32s3TouchLCD4b() : boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeTca9554(); + InitializeAxp2101(); + InitializeRGB(); + InitializeTouch(); + InitializeButtons(); + InitializeTools(); + InitializeKeyMonitor(); // 启动按键监听 + GetBacklight()->SetBrightness(100); + } + + virtual AudioCodec* GetAudioCodec() override { + static BoxAudioCodec audio_codec( + i2c_bus_, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_CODEC_ES7210_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int &level, bool &charging, bool &discharging) override { + static bool last_discharging = false; + charging = pmic_->IsCharging(); + discharging = pmic_->IsDischarging(); + if (discharging != last_discharging) + { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + + level = pmic_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) + { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(WaveshareEsp32s3TouchLCD4b); diff --git a/main/boards/wireless-tag-wtp4c5mp07s/README.md b/main/boards/wireless-tag-wtp4c5mp07s/README.md new file mode 100644 index 0000000..381aa92 --- /dev/null +++ b/main/boards/wireless-tag-wtp4c5mp07s/README.md @@ -0,0 +1,45 @@ +## Wireless-Tag WTP4C5MP07S + +[Wireless-Tag WTP4C5MP07S](https://shop.wireless-tag.com/products/7inch-lcd-touch-screen-1024x600-mipi-smart-displays-wtp4c5mp07s-esp32-lcd-board-used-with-esp32-p4-and-esp32-c5-dev-board) product is a combo of +* [Wireless-Tag WT99P4C5-S1](https://en.wireless-tag.com/product-item-66.html) ESP32-P4 development board and +* 7 inch 1024x600 ZX7D00C1060M002A MIPI DSI LCD display + +
+ +## Configuration + +### ESP32P4 Configuration + +* Set the compilation target to ESP32P4 + + idf.py set-target esp32p4 + +* Open menuconfig + + idf.py menuconfig + +* Select the board + + Xiaozhi Assistant -> Board Type -> Wireless-Tag WTP4C5MP07S + +* Select PSRAM + + Component config -> ESP PSRAM -> PSRAM config -> Try to allocate memories of WiFi and LWIP in SPIRAM firstly -> No + +* Select Wi-Fi slave target + + Component config -> Wi-Fi Remote -> choose slave target -> esp32c5 + +* Select Wi-Fi buffers + + Component config -> Wi-Fi Remote -> Wi-Fi configuration -> Max number of WiFi static RX buffers -> 10 + Component config -> Wi-Fi Remote -> Wi-Fi configuration -> Max number of WiFi dynamic RX buffers -> 24 + Component config -> Wi-Fi Remote -> Wi-Fi configuration -> Max number of WiFi static TX buffers -> 10 + +* Build + + idf.py build + +### ESP32C5 Configuration + +* Flash the slave example from the esp-hosted-mcu library for the target chip ESP32C5. The esp-hosted-mcu version must match the one used in the xiaozhi-esp32 library. diff --git a/main/boards/wireless-tag-wtp4c5mp07s/config.h b/main/boards/wireless-tag-wtp4c5mp07s/config.h new file mode 100644 index 0000000..b3ae81e --- /dev/null +++ b/main/boards/wireless-tag-wtp4c5mp07s/config.h @@ -0,0 +1,104 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_10 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_9 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_53 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_7 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_8 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_GPIO GPIO_NUM_35 + +#define DISPLAY_WIDTH 1024 +#define DISPLAY_HEIGHT 600 + +#define LCD_BIT_PER_PIXEL (16) +#define PIN_NUM_LCD_RST GPIO_NUM_23 + +#define DELAY_TIME_MS (3000) +#define LCD_MIPI_DSI_LANE_NUM (2) // 2 data lanes + +#define MIPI_DSI_PHY_PWR_LDO_CHAN (3) +#define MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV (2500) + +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +// SD Card configuration (disabled by default) +// Enable one of the following by setting to 1 and set pins accordingly. +// Note: SDMMC may conflict with ESP-Hosted SDIO. If using ESP-Hosted via SDIO, +// prefer SDSPI mode for SD card or disable hosted SDIO. + +// SDMMC 1-bit/4-bit mode +#ifndef SDCARD_SDMMC_ENABLED +#define SDCARD_SDMMC_ENABLED 0 +#endif +// SDMMC bus width: set to 1 or 4 +#ifndef SDCARD_SDMMC_BUS_WIDTH +// Use 4-bit bus width when enabling SDMMC +#define SDCARD_SDMMC_BUS_WIDTH 4 +#endif +// SDMMC pin assignments (set to actual pins when enabling SDMMC) +#ifndef SDCARD_SDMMC_CLK_PIN +#define SDCARD_SDMMC_CLK_PIN GPIO_NUM_43 // BSP_SD_CLK +#endif +#ifndef SDCARD_SDMMC_CMD_PIN +#define SDCARD_SDMMC_CMD_PIN GPIO_NUM_44 // BSP_SD_CMD +#endif +#ifndef SDCARD_SDMMC_D0_PIN +#define SDCARD_SDMMC_D0_PIN GPIO_NUM_39 // BSP_SD_D0 +#endif +#ifndef SDCARD_SDMMC_D1_PIN +#define SDCARD_SDMMC_D1_PIN GPIO_NUM_40 // BSP_SD_D1 +#endif +#ifndef SDCARD_SDMMC_D2_PIN +#define SDCARD_SDMMC_D2_PIN GPIO_NUM_41 // BSP_SD_D2 +#endif +#ifndef SDCARD_SDMMC_D3_PIN +#define SDCARD_SDMMC_D3_PIN GPIO_NUM_42 // BSP_SD_D3 +#endif + +// SDSPI mode (uses SPI bus) +#ifndef SDCARD_SDSPI_ENABLED +#define SDCARD_SDSPI_ENABLED 1 +#endif +#ifndef SDCARD_SPI_HOST +#define SDCARD_SPI_HOST SPI3_HOST +#endif +#ifndef SDCARD_SPI_MOSI +#define SDCARD_SPI_MOSI GPIO_NUM_44 // BSP_SD_SPI_MOSI +#endif +#ifndef SDCARD_SPI_MISO +#define SDCARD_SPI_MISO GPIO_NUM_39 // BSP_SD_SPI_MISO +#endif +#ifndef SDCARD_SPI_SCLK +#define SDCARD_SPI_SCLK GPIO_NUM_43 // BSP_SD_SPI_CLK +#endif +#ifndef SDCARD_SPI_CS +#define SDCARD_SPI_CS GPIO_NUM_42 // BSP_SD_SPI_CS +#endif + +#ifndef SDCARD_MOUNT_POINT +#define SDCARD_MOUNT_POINT "/sdcard" +#endif + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/wireless-tag-wtp4c5mp07s/config.json b/main/boards/wireless-tag-wtp4c5mp07s/config.json new file mode 100644 index 0000000..272ecfd --- /dev/null +++ b/main/boards/wireless-tag-wtp4c5mp07s/config.json @@ -0,0 +1,16 @@ +{ + "target": "esp32p4", + "builds": [ + { + "name": "wireless-tag-wtp4c5mp07s", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=n", + "CONFIG_SLAVE_IDF_TARGET_ESP32C5=y", + "CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP=n", + "CONFIG_WIFI_RMT_STATIC_RX_BUFFER_NUM=10", + "CONFIG_WIFI_RMT_DYNAMIC_RX_BUFFER_NUM=24", + "CONFIG_WIFI_RMT_STATIC_TX_BUFFER_NUM=10" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/wireless-tag-wtp4c5mp07s/wireless-tag-wtp4c5mp07s.cc b/main/boards/wireless-tag-wtp4c5mp07s/wireless-tag-wtp4c5mp07s.cc new file mode 100644 index 0000000..28250fb --- /dev/null +++ b/main/boards/wireless-tag-wtp4c5mp07s/wireless-tag-wtp4c5mp07s.cc @@ -0,0 +1,295 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "application.h" +#include "display/lcd_display.h" +// #include "display/no_display.h" +#include "button.h" +#include "config.h" + +#include "esp_lcd_panel_ops.h" +#include "esp_lcd_mipi_dsi.h" +#include "esp_ldo_regulator.h" + +#include "esp_lcd_ek79007.h" + +#include +#include +#include +#include +#include "esp_lcd_touch_gt911.h" + +#include +#include +#include +#include +#include "sd_pwr_ctrl_by_on_chip_ldo.h" + +#define TAG "WirelessTagEsp32p47b" + +class WirelessTagEsp32p47b : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + LcdDisplay *display_; + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_1, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + } + + static esp_err_t bsp_enable_dsi_phy_power(void) { +#if MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + // Turn on the power for MIPI DSI PHY, so it can go from "No Power" state to "Shutdown" state + static esp_ldo_channel_handle_t phy_pwr_chan = NULL; + esp_ldo_channel_config_t ldo_cfg = { + .chan_id = MIPI_DSI_PHY_PWR_LDO_CHAN, + .voltage_mv = MIPI_DSI_PHY_PWR_LDO_VOLTAGE_MV, + }; + esp_ldo_acquire_channel(&ldo_cfg, &phy_pwr_chan); + ESP_LOGI(TAG, "MIPI DSI PHY Powered on"); +#endif // BSP_MIPI_DSI_PHY_PWR_LDO_CHAN > 0 + + return ESP_OK; + } + + void InitializeLCD() { + bsp_enable_dsi_phy_power(); + esp_lcd_panel_io_handle_t io = NULL; + esp_lcd_panel_handle_t disp_panel = NULL; + + esp_lcd_dsi_bus_handle_t mipi_dsi_bus = NULL; + esp_lcd_dsi_bus_config_t bus_config = { + .bus_id = 0, + .num_data_lanes = 2, + .lane_bit_rate_mbps = 900, + }; + esp_lcd_new_dsi_bus(&bus_config, &mipi_dsi_bus); + + ESP_LOGI(TAG, "Install MIPI DSI LCD control panel"); + // we use DBI interface to send LCD commands and parameters + esp_lcd_dbi_io_config_t dbi_config = EK79007_PANEL_IO_DBI_CONFIG(); + esp_lcd_new_panel_io_dbi(mipi_dsi_bus, &dbi_config, &io); + + esp_lcd_dpi_panel_config_t dpi_config = { + .dpi_clk_src = MIPI_DSI_DPI_CLK_SRC_DEFAULT, + .dpi_clock_freq_mhz = 52, + .pixel_format = LCD_COLOR_PIXEL_FORMAT_RGB565, + .num_fbs = 1, + .video_timing = { + .h_size = 1024, + .v_size = 600, + .hsync_pulse_width = 10, + .hsync_back_porch = 160, + .hsync_front_porch = 160, + .vsync_pulse_width = 1, + .vsync_back_porch = 23, + .vsync_front_porch = 12, + }, + .flags = { + .use_dma2d = true, + }, + }; + ek79007_vendor_config_t vendor_config = { + .mipi_config = { + .dsi_bus = mipi_dsi_bus, + .dpi_config = &dpi_config, + }, + }; + + const esp_lcd_panel_dev_config_t lcd_dev_config = { + .reset_gpio_num = PIN_NUM_LCD_RST, + .rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB, + .bits_per_pixel = 16, + .flags = { + .reset_active_high = true, + }, + .vendor_config = &vendor_config, + }; + esp_lcd_new_panel_ek79007(io, &lcd_dev_config, &disp_panel); + esp_lcd_panel_reset(disp_panel); + esp_lcd_panel_init(disp_panel); + + display_ = new MipiLcdDisplay(io, disp_panel, DISPLAY_WIDTH, DISPLAY_HEIGHT, + DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); +#if 0 + lv_display_t *disp = lv_display_get_default(); + if (disp) { + lv_disp_set_rotation(disp, LV_DISPLAY_ROTATION_180); + ESP_LOGI(TAG, "Display rotated 180 degrees"); + } else { + ESP_LOGE(TAG, "Failed to get default display for rotation"); + } +#endif + } + + void InitializeTouch() + { + esp_lcd_touch_handle_t tp; + esp_lcd_touch_config_t tp_cfg = { + .x_max = DISPLAY_WIDTH, + .y_max = DISPLAY_HEIGHT, + .rst_gpio_num = GPIO_NUM_NC, + .int_gpio_num = GPIO_NUM_21, + .levels = { + .reset = 1, + .interrupt = 0, + }, + .flags = { + .swap_xy = DISPLAY_SWAP_XY, + .mirror_x = DISPLAY_MIRROR_X, + .mirror_y = DISPLAY_MIRROR_Y, + }, + }; + esp_lcd_panel_io_handle_t tp_io_handle = NULL; + esp_lcd_panel_io_i2c_config_t tp_io_config = ESP_LCD_TOUCH_IO_I2C_GT911_CONFIG(); + tp_io_config.scl_speed_hz = 400 * 1000; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c(i2c_bus_, &tp_io_config, &tp_io_handle)); + ESP_LOGI(TAG, "Initialize touch controller"); + ESP_ERROR_CHECK(esp_lcd_touch_new_i2c_gt911(tp_io_handle, &tp_cfg, &tp)); + const lvgl_port_touch_cfg_t touch_cfg = { + .disp = lv_display_get_default(), + .handle = tp, + }; + lvgl_port_add_touch(&touch_cfg); + ESP_LOGI(TAG, "Touch panel initialized successfully"); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); }); + } + + void InitializeSdCard() { +#if SDCARD_SDMMC_ENABLED + sd_pwr_ctrl_handle_t sd_ldo = NULL; + sd_pwr_ctrl_ldo_config_t ldo_cfg = { .ldo_chan_id = 4 }; + if (sd_pwr_ctrl_new_on_chip_ldo(&ldo_cfg, &sd_ldo) == ESP_OK) { + ESP_LOGI(TAG, "SD LDO channel 4 enabled"); + } else { + ESP_LOGW(TAG, "Failed to enable SD LDO channel 4"); + } + sdmmc_host_t host = SDMMC_HOST_DEFAULT(); + sdmmc_slot_config_t slot_config = SDMMC_SLOT_CONFIG_DEFAULT(); + // Map pins via GPIO matrix if needed + slot_config.clk = SDCARD_SDMMC_CLK_PIN; + slot_config.cmd = SDCARD_SDMMC_CMD_PIN; + slot_config.d0 = SDCARD_SDMMC_D0_PIN; + slot_config.width = SDCARD_SDMMC_BUS_WIDTH; + if (SDCARD_SDMMC_BUS_WIDTH == 4) { + slot_config.d1 = SDCARD_SDMMC_D1_PIN; + slot_config.d2 = SDCARD_SDMMC_D2_PIN; + slot_config.d3 = SDCARD_SDMMC_D3_PIN; + } + + esp_vfs_fat_sdmmc_mount_config_t mount_config = { + .format_if_mount_failed = false, + .max_files = 5, + .allocation_unit_size = 0, + .disk_status_check_enable = true, + }; + sdmmc_card_t* card; + host.pwr_ctrl_handle = sd_ldo; + esp_err_t ret = esp_vfs_fat_sdmmc_mount(SDCARD_MOUNT_POINT, &host, &slot_config, &mount_config, &card); + if (ret == ESP_OK) { + sdmmc_card_print_info(stdout, card); + ESP_LOGI(TAG, "SD card mounted at %s (SDMMC)", SDCARD_MOUNT_POINT); + } else { + ESP_LOGW(TAG, "Failed to mount SD card (SDMMC): %s", esp_err_to_name(ret)); + } +#elif SDCARD_SDSPI_ENABLED + sd_pwr_ctrl_handle_t sd_ldo = NULL; + sd_pwr_ctrl_ldo_config_t ldo_cfg = { .ldo_chan_id = 4 }; + if (sd_pwr_ctrl_new_on_chip_ldo(&ldo_cfg, &sd_ldo) == ESP_OK) { + ESP_LOGI(TAG, "SD LDO channel 4 enabled"); + } else { + ESP_LOGW(TAG, "Failed to enable SD LDO channel 4"); + } + sdmmc_host_t host = SDSPI_HOST_DEFAULT(); + spi_bus_config_t bus_cfg = { + .mosi_io_num = SDCARD_SPI_MOSI, + .miso_io_num = SDCARD_SPI_MISO, + .sclk_io_num = SDCARD_SPI_SCLK, + .quadwp_io_num = -1, + .quadhd_io_num = -1, + .max_transfer_sz = 4000, + }; + ESP_ERROR_CHECK_WITHOUT_ABORT(spi_bus_initialize((spi_host_device_t)SDCARD_SPI_HOST, &bus_cfg, SPI_DMA_CH_AUTO)); + sdspi_device_config_t slot_config = SDSPI_DEVICE_CONFIG_DEFAULT(); + slot_config.gpio_cs = SDCARD_SPI_CS; + slot_config.host_id = (spi_host_device_t)SDCARD_SPI_HOST; + + esp_vfs_fat_sdmmc_mount_config_t mount_config = { + .format_if_mount_failed = false, + .max_files = 5, + .allocation_unit_size = 0, + .disk_status_check_enable = true, + }; + sdmmc_card_t* card; + host.pwr_ctrl_handle = sd_ldo; + esp_err_t ret = esp_vfs_fat_sdspi_mount(SDCARD_MOUNT_POINT, &host, &slot_config, &mount_config, &card); + if (ret == ESP_OK) { + sdmmc_card_print_info(stdout, card); + ESP_LOGI(TAG, "SD card mounted at %s (SDSPI)", SDCARD_MOUNT_POINT); + } else { + ESP_LOGW(TAG, "Failed to mount SD card (SDSPI): %s", esp_err_to_name(ret)); + } +#else + ESP_LOGI(TAG, "SD card disabled (enable SDCARD_SDMMC_ENABLED or SDCARD_SDSPI_ENABLED)"); +#endif + } + +public: + WirelessTagEsp32p47b() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeLCD(); + InitializeTouch(); + InitializeSdCard(); + InitializeButtons(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_1, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual Display *GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + +}; + +DECLARE_BOARD(WirelessTagEsp32p47b); diff --git a/main/boards/xingzhi-cube-0.85tft-ml307/config.h b/main/boards/xingzhi-cube-0.85tft-ml307/config.h new file mode 100644 index 0000000..7388d39 --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-ml307/config.h @@ -0,0 +1,40 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA GPIO_NUM_10 +#define DISPLAY_SCL GPIO_NUM_9 +#define DISPLAY_DC GPIO_NUM_8 +#define DISPLAY_CS GPIO_NUM_14 +#define DISPLAY_RES GPIO_NUM_18 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-0.85tft-ml307/config.json b/main/boards/xingzhi-cube-0.85tft-ml307/config.json new file mode 100644 index 0000000..0305c46 --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-ml307/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-0.85tft-ml307", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-0.85tft-ml307/xingzhi-cube-0.85tft-ml307.cc b/main/boards/xingzhi-cube-0.85tft-ml307/xingzhi-cube-0.85tft-ml307.cc new file mode 100644 index 0000000..2d2f36e --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-ml307/xingzhi-cube-0.85tft-ml307.cc @@ -0,0 +1,240 @@ +#include "ml307_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "../xingzhi-cube-1.54tft-wifi/power_manager.h" + +#include +#include +#include + +#include +#include + +#include +#include "settings.h" + +#define TAG "XINGZHI_CUBE_0_85TFT_ML307" + +static const nv3023_lcd_init_cmd_t lcd_init_cmds[] = { + {0xff, (uint8_t[]){0xa5}, 1, 0}, + {0x3E, (uint8_t[]){0x09}, 1, 0}, + {0x3A, (uint8_t[]){0x65}, 1, 0}, + {0x82, (uint8_t[]){0x00}, 1, 0}, + {0x98, (uint8_t[]){0x00}, 1, 0}, + {0x63, (uint8_t[]){0x0f}, 1, 0}, + {0x64, (uint8_t[]){0x0f}, 1, 0}, + {0xB4, (uint8_t[]){0x34}, 1, 0}, + {0xB5, (uint8_t[]){0x30}, 1, 0}, + {0x83, (uint8_t[]){0x03}, 1, 0}, + {0x86, (uint8_t[]){0x04}, 1, 0}, + {0x87, (uint8_t[]){0x16}, 1, 0}, + {0x88, (uint8_t[]){0x0A}, 1, 0}, + {0x89, (uint8_t[]){0x27}, 1, 0}, + {0x93, (uint8_t[]){0x63}, 1, 0}, + {0x96, (uint8_t[]){0x81}, 1, 0}, + {0xC3, (uint8_t[]){0x10}, 1, 0}, + {0xE6, (uint8_t[]){0x00}, 1, 0}, + {0x99, (uint8_t[]){0x01}, 1, 0}, + {0x70, (uint8_t[]){0x09}, 1, 0}, + {0x71, (uint8_t[]){0x1D}, 1, 0}, + {0x72, (uint8_t[]){0x14}, 1, 0}, + {0x73, (uint8_t[]){0x0a}, 1, 0}, + {0x74, (uint8_t[]){0x11}, 1, 0}, + {0x75, (uint8_t[]){0x16}, 1, 0}, + {0x76, (uint8_t[]){0x38}, 1, 0}, + {0x77, (uint8_t[]){0x0B}, 1, 0}, + {0x78, (uint8_t[]){0x08}, 1, 0}, + {0x79, (uint8_t[]){0x3E}, 1, 0}, + {0x7a, (uint8_t[]){0x07}, 1, 0}, + {0x7b, (uint8_t[]){0x0D}, 1, 0}, + {0x7c, (uint8_t[]){0x16}, 1, 0}, + {0x7d, (uint8_t[]){0x0F}, 1, 0}, + {0x7e, (uint8_t[]){0x14}, 1, 0}, + {0x7f, (uint8_t[]){0x05}, 1, 0}, + {0xa0, (uint8_t[]){0x04}, 1, 0}, + {0xa1, (uint8_t[]){0x28}, 1, 0}, + {0xa2, (uint8_t[]){0x0c}, 1, 0}, + {0xa3, (uint8_t[]){0x11}, 1, 0}, + {0xa4, (uint8_t[]){0x0b}, 1, 0}, + {0xa5, (uint8_t[]){0x23}, 1, 0}, + {0xa6, (uint8_t[]){0x45}, 1, 0}, + {0xa7, (uint8_t[]){0x07}, 1, 0}, + {0xa8, (uint8_t[]){0x0a}, 1, 0}, + {0xa9, (uint8_t[]){0x3b}, 1, 0}, + {0xaa, (uint8_t[]){0x0d}, 1, 0}, + {0xab, (uint8_t[]){0x18}, 1, 0}, + {0xac, (uint8_t[]){0x14}, 1, 0}, + {0xad, (uint8_t[]){0x0F}, 1, 0}, + {0xae, (uint8_t[]){0x19}, 1, 0}, + {0xaf, (uint8_t[]){0x08}, 1, 0}, + {0xff, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0x29, (uint8_t[]){0x00}, 0, 10} +}; + +class XINGZHI_CUBE_0_85TFT_ML307 : public Ml307Board { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_HEIGHT * 80 *sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + app.ToggleChatState(); + }); + } + + void InitializeNv3023Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = NV3023_PANEL_IO_SPI_CONFIG(DISPLAY_CS, DISPLAY_DC, NULL, NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + nv3023_vendor_config_t vendor_config = { // Uncomment these lines if use custom initialization commands + .init_cmds = lcd_init_cmds, + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(nv3023_lcd_init_cmd_t), + }; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_nv3023(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new SpiLcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void Initializegpio21_45() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + //gpio_num_t sp_45 = GPIO_NUM_45; + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << GPIO_NUM_45); + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + io_conf.pull_down_en = GPIO_PULLDOWN_ENABLE; + gpio_config(&io_conf); + gpio_set_level(GPIO_NUM_45, 0); + } + +public: + XINGZHI_CUBE_0_85TFT_ML307(): Ml307Board(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + Initializegpio21_45(); // 初始时,拉高21引脚,保证4g模块正常工作 + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeNv3023Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + Ml307Board::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_0_85TFT_ML307); diff --git a/main/boards/xingzhi-cube-0.85tft-wifi/config.h b/main/boards/xingzhi-cube-0.85tft-wifi/config.h new file mode 100644 index 0000000..8b2bf9d --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-wifi/config.h @@ -0,0 +1,37 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_NC +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_NC + +#define DISPLAY_SDA GPIO_NUM_10 +#define DISPLAY_SCL GPIO_NUM_9 +#define DISPLAY_DC GPIO_NUM_8 +#define DISPLAY_CS GPIO_NUM_14 +#define DISPLAY_RES GPIO_NUM_18 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 128 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-0.85tft-wifi/config.json b/main/boards/xingzhi-cube-0.85tft-wifi/config.json new file mode 100644 index 0000000..867160f --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-wifi/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-0.85tft-wifi", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-0.85tft-wifi/xingzhi-cube-0.85tft-wifi.cc b/main/boards/xingzhi-cube-0.85tft-wifi/xingzhi-cube-0.85tft-wifi.cc new file mode 100644 index 0000000..37d56e4 --- /dev/null +++ b/main/boards/xingzhi-cube-0.85tft-wifi/xingzhi-cube-0.85tft-wifi.cc @@ -0,0 +1,244 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "../xingzhi-cube-1.54tft-wifi/power_manager.h" + +#include +#include +#include + +#include +#include + +#include +#include "settings.h" + +#define TAG "XINGZHI_CUBE_0_85TFT_WIFI" + +static const nv3023_lcd_init_cmd_t lcd_init_cmds[] = { + {0xff, (uint8_t[]){0xa5}, 1, 0}, + {0x3E, (uint8_t[]){0x09}, 1, 0}, + {0x3A, (uint8_t[]){0x65}, 1, 0}, + {0x82, (uint8_t[]){0x00}, 1, 0}, + {0x98, (uint8_t[]){0x00}, 1, 0}, + {0x63, (uint8_t[]){0x0f}, 1, 0}, + {0x64, (uint8_t[]){0x0f}, 1, 0}, + {0xB4, (uint8_t[]){0x34}, 1, 0}, + {0xB5, (uint8_t[]){0x30}, 1, 0}, + {0x83, (uint8_t[]){0x03}, 1, 0}, + {0x86, (uint8_t[]){0x04}, 1, 0}, + {0x87, (uint8_t[]){0x16}, 1, 0}, + {0x88, (uint8_t[]){0x0A}, 1, 0}, + {0x89, (uint8_t[]){0x27}, 1, 0}, + {0x93, (uint8_t[]){0x63}, 1, 0}, + {0x96, (uint8_t[]){0x81}, 1, 0}, + {0xC3, (uint8_t[]){0x10}, 1, 0}, + {0xE6, (uint8_t[]){0x00}, 1, 0}, + {0x99, (uint8_t[]){0x01}, 1, 0}, + {0x70, (uint8_t[]){0x09}, 1, 0}, + {0x71, (uint8_t[]){0x1D}, 1, 0}, + {0x72, (uint8_t[]){0x14}, 1, 0}, + {0x73, (uint8_t[]){0x0a}, 1, 0}, + {0x74, (uint8_t[]){0x11}, 1, 0}, + {0x75, (uint8_t[]){0x16}, 1, 0}, + {0x76, (uint8_t[]){0x38}, 1, 0}, + {0x77, (uint8_t[]){0x0B}, 1, 0}, + {0x78, (uint8_t[]){0x08}, 1, 0}, + {0x79, (uint8_t[]){0x3E}, 1, 0}, + {0x7a, (uint8_t[]){0x07}, 1, 0}, + {0x7b, (uint8_t[]){0x0D}, 1, 0}, + {0x7c, (uint8_t[]){0x16}, 1, 0}, + {0x7d, (uint8_t[]){0x0F}, 1, 0}, + {0x7e, (uint8_t[]){0x14}, 1, 0}, + {0x7f, (uint8_t[]){0x05}, 1, 0}, + {0xa0, (uint8_t[]){0x04}, 1, 0}, + {0xa1, (uint8_t[]){0x28}, 1, 0}, + {0xa2, (uint8_t[]){0x0c}, 1, 0}, + {0xa3, (uint8_t[]){0x11}, 1, 0}, + {0xa4, (uint8_t[]){0x0b}, 1, 0}, + {0xa5, (uint8_t[]){0x23}, 1, 0}, + {0xa6, (uint8_t[]){0x45}, 1, 0}, + {0xa7, (uint8_t[]){0x07}, 1, 0}, + {0xa8, (uint8_t[]){0x0a}, 1, 0}, + {0xa9, (uint8_t[]){0x3b}, 1, 0}, + {0xaa, (uint8_t[]){0x0d}, 1, 0}, + {0xab, (uint8_t[]){0x18}, 1, 0}, + {0xac, (uint8_t[]){0x14}, 1, 0}, + {0xad, (uint8_t[]){0x0F}, 1, 0}, + {0xae, (uint8_t[]){0x19}, 1, 0}, + {0xaf, (uint8_t[]){0x08}, 1, 0}, + {0xff, (uint8_t[]){0x00}, 1, 0}, + {0x11, (uint8_t[]){0x00}, 0, 120}, + {0x29, (uint8_t[]){0x00}, 0, 10} +}; + +class XINGZHI_CUBE_0_85TFT_WIFI : public WifiBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_HEIGHT * 80 *sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + } + + void InitializeNv3023Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = NV3023_PANEL_IO_SPI_CONFIG(DISPLAY_CS, DISPLAY_DC, NULL, NULL); + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi((esp_lcd_spi_bus_handle_t)SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + nv3023_vendor_config_t vendor_config = { // Uncomment these lines if use custom initialization commands + .init_cmds = lcd_init_cmds, + .init_cmds_size = sizeof(lcd_init_cmds) / sizeof(nv3023_lcd_init_cmd_t), + }; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_BGR; + panel_config.bits_per_pixel = 16; + panel_config.vendor_config = &vendor_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_nv3023(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, false)); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new SpiLcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void Initializegpio21_45() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + //gpio_num_t sp_45 = GPIO_NUM_45; + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_OUTPUT; + io_conf.pin_bit_mask = (1ULL << GPIO_NUM_45); + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + io_conf.pull_down_en = GPIO_PULLDOWN_ENABLE; + gpio_config(&io_conf); + gpio_set_level(GPIO_NUM_45, 0); + } + +public: + XINGZHI_CUBE_0_85TFT_WIFI(): + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + Initializegpio21_45(); // 初始时,拉高21引脚,保证4g模块正常工作 + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeNv3023Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_0_85TFT_WIFI); diff --git a/main/boards/xingzhi-cube-0.96oled-ml307/config.h b/main/boards/xingzhi-cube-0.96oled-ml307/config.h new file mode 100644 index 0000000..0f3f8ce --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-ml307/config.h @@ -0,0 +1,30 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA_PIN GPIO_NUM_41 +#define DISPLAY_SCL_PIN GPIO_NUM_42 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-0.96oled-ml307/config.json b/main/boards/xingzhi-cube-0.96oled-ml307/config.json new file mode 100644 index 0000000..be5919c --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-ml307/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-0.96oled-ml307", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-0.96oled-ml307/xingzhi-cube-0.96oled-ml307.cc b/main/boards/xingzhi-cube-0.96oled-ml307/xingzhi-cube-0.96oled-ml307.cc new file mode 100644 index 0000000..18f7a01 --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-ml307/xingzhi-cube-0.96oled-ml307.cc @@ -0,0 +1,234 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "display/oled_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "../xingzhi-cube-1.54tft-wifi/power_manager.h" + +#include +#include +#include +#include +#include +#include +#include + +#define TAG "XINGZHI_CUBE_0_96OLED_ML307" + +class XINGZHI_CUBE_0_96OLED_ML307 : public DualNetworkBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + Display* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + +public: + XINGZHI_CUBE_0_96OLED_ML307() : DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_0_96OLED_ML307); diff --git a/main/boards/xingzhi-cube-0.96oled-wifi/config.h b/main/boards/xingzhi-cube-0.96oled-wifi/config.h new file mode 100644 index 0000000..b353890 --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-wifi/config.h @@ -0,0 +1,27 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BUILTIN_LED_GPIO GPIO_NUM_48 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA_PIN GPIO_NUM_41 +#define DISPLAY_SCL_PIN GPIO_NUM_42 +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-0.96oled-wifi/config.json b/main/boards/xingzhi-cube-0.96oled-wifi/config.json new file mode 100644 index 0000000..2cba4c6 --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-wifi/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-0.96oled-wifi", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-0.96oled-wifi/xingzhi-cube-0.96oled-wifi.cc b/main/boards/xingzhi-cube-0.96oled-wifi/xingzhi-cube-0.96oled-wifi.cc new file mode 100644 index 0000000..d2f0685 --- /dev/null +++ b/main/boards/xingzhi-cube-0.96oled-wifi/xingzhi-cube-0.96oled-wifi.cc @@ -0,0 +1,225 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/oled_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_save_timer.h" +#include "../xingzhi-cube-1.54tft-wifi/power_manager.h" + +#include + +#include +#include +#include +#include +#include +#include + +#define TAG "XINGZHI_CUBE_0_96OLED_WIFI" + +class XINGZHI_CUBE_0_96OLED_WIFI : public WifiBoard { +private: + i2c_master_bus_handle_t display_i2c_bus_; + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + Display* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeDisplayI2c() { + i2c_master_bus_config_t bus_config = { + .i2c_port = (i2c_port_t)0, + .sda_io_num = DISPLAY_SDA_PIN, + .scl_io_num = DISPLAY_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&bus_config, &display_i2c_bus_)); + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(display_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + +public: + XINGZHI_CUBE_0_96OLED_WIFI() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeDisplayI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_0_96OLED_WIFI); diff --git a/main/boards/xingzhi-cube-1.54tft-ml307/config.h b/main/boards/xingzhi-cube-1.54tft-ml307/config.h new file mode 100644 index 0000000..9167578 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-ml307/config.h @@ -0,0 +1,40 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA GPIO_NUM_10 +#define DISPLAY_SCL GPIO_NUM_9 +#define DISPLAY_DC GPIO_NUM_8 +#define DISPLAY_CS GPIO_NUM_14 +#define DISPLAY_RES GPIO_NUM_18 +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-1.54tft-ml307/config.json b/main/boards/xingzhi-cube-1.54tft-ml307/config.json new file mode 100644 index 0000000..e3d5f50 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-ml307/config.json @@ -0,0 +1,15 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-1.54tft-ml307", + "sdkconfig_append": [] + }, + { + "name": "xingzhi-cube-1.54tft-ml307-wechatui", + "sdkconfig_append": [ + "CONFIG_USE_WECHAT_MESSAGE_STYLE=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-1.54tft-ml307/xingzhi-cube-1.54tft-ml307.cc b/main/boards/xingzhi-cube-1.54tft-ml307/xingzhi-cube-1.54tft-ml307.cc new file mode 100644 index 0000000..72aff95 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-ml307/xingzhi-cube-1.54tft-ml307.cc @@ -0,0 +1,212 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "../xingzhi-cube-1.54tft-wifi/power_manager.h" + +#include +#include +#include + +#include +#include + +#define TAG "XINGZHI_CUBE_1_54TFT_ML307" + +class XINGZHI_CUBE_1_54TFT_ML307 : public DualNetworkBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, true)); + + display_ = new SpiLcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + XINGZHI_CUBE_1_54TFT_ML307() : + DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_1_54TFT_ML307); diff --git a/main/boards/xingzhi-cube-1.54tft-wifi/config.h b/main/boards/xingzhi-cube-1.54tft-wifi/config.h new file mode 100644 index 0000000..c1a998a --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-wifi/config.h @@ -0,0 +1,36 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_40 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA GPIO_NUM_10 +#define DISPLAY_SCL GPIO_NUM_9 +#define DISPLAY_DC GPIO_NUM_8 +#define DISPLAY_CS GPIO_NUM_14 +#define DISPLAY_RES GPIO_NUM_18 +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-cube-1.54tft-wifi/config.json b/main/boards/xingzhi-cube-1.54tft-wifi/config.json new file mode 100644 index 0000000..6cfa0d3 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-wifi/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-cube-1.54tft-wifi", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-cube-1.54tft-wifi/power_manager.h b/main/boards/xingzhi-cube-1.54tft-wifi/power_manager.h new file mode 100644 index 0000000..8d238f2 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-wifi/power_manager.h @@ -0,0 +1,186 @@ +#pragma once +#include +#include + +#include +#include +#include + + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + adc_oneshot_unit_handle_t adc_handle_; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_6, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1970, 0}, + {2062, 20}, + {2154, 40}, + {2246, 60}, + {2338, 80}, + {2430, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_2, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_6, &chan_config)); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/xingzhi-cube-1.54tft-wifi/xingzhi-cube-1.54tft-wifi.cc b/main/boards/xingzhi-cube-1.54tft-wifi/xingzhi-cube-1.54tft-wifi.cc new file mode 100644 index 0000000..8827b37 --- /dev/null +++ b/main/boards/xingzhi-cube-1.54tft-wifi/xingzhi-cube-1.54tft-wifi.cc @@ -0,0 +1,201 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include +#include +#include + +#include +#include + +#define TAG "XINGZHI_CUBE_1_54TFT_WIFI" + +class XINGZHI_CUBE_1_54TFT_WIFI : public WifiBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_38); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_21); + rtc_gpio_set_direction(GPIO_NUM_21, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_21, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + rtc_gpio_set_level(GPIO_NUM_21, 0); + // 启用保持功能,确保睡眠期间电平不变 + rtc_gpio_hold_en(GPIO_NUM_21); + esp_lcd_panel_disp_on_off(panel_, false); //关闭显示 + esp_deep_sleep_start(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, true)); + + display_ = new SpiLcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + +public: + XINGZHI_CUBE_1_54TFT_WIFI() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_CUBE_1_54TFT_WIFI); diff --git a/main/boards/xingzhi-metal-1.54-wifi/README.md b/main/boards/xingzhi-metal-1.54-wifi/README.md new file mode 100644 index 0000000..2ad3efd --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/README.md @@ -0,0 +1,61 @@ +# 无名科技星智 1.54 METAL (wifi) + +## 简介 +无名科技星智 1.54 METAL (wifi) 是星智 1.54 开模版的升级款,配备 1.54 寸 LCD 屏幕与 CST816 触摸芯片。它用触摸交互替代物理按键,并将外壳升级为铝合金材质,同步优化了交互体验与产品质感、手感。 + +>### 按键操作 +>- **开机**: 关机状态,长按电源键3秒后自动开机(旧版硬件长按电源键1s后自动开机) +>- **关机**: 开机状态,长按电源键5秒后自动关机(旧版硬件插入usb时不会自动关机) +>- **唤醒/打断**: 正常通话环境下,单击中间触摸按键 +>- **重新配网**: 开机后,1秒钟内单击中间触摸按键,会自动重启并进入配网界面 +>- **增加音量**: 开机状态下,单击右侧触摸按键,音量增加。长按右侧触摸按键2s,音量递增。 +>- **减小音量**: 开机状态下,单击左侧触摸按键,音量减小。长按左侧触摸按键2s,音量递减。 + +>### 休眠操作 +>- **浅睡眠**: 开机后,维持待命状态60s后,进入浅睡眠(屏幕亮度调整到1%) +>- **深睡眠**: 开机后,维持待命状态300s后,进入深睡眠(自动关机) +>- **唤醒**: 浅睡眠状态下,单击中间触摸按键,唤醒设备(屏幕亮度回调) + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +- `Xiaozhi Assistant` → `Board Type` → 选择 `无名科技星智1.54 METAL(wifi)` +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` \ No newline at end of file diff --git a/main/boards/xingzhi-metal-1.54-wifi/config.h b/main/boards/xingzhi-metal-1.54-wifi/config.h new file mode 100644 index 0000000..11dab54 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/config.h @@ -0,0 +1,53 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +// 音频 +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_INPUT_REFERENCE true +#define AUDIO_I2S_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_17 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_15 + +#define AUDIO_CODEC_USE_PCA9557 +#define AUDIO_CODEC_I2C_PA_EN GPIO_NUM_21 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_41 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_42 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +// 按键 +#define BOOT_BUTTON_GPIO GPIO_NUM_0 + +// 屏幕 +#define DISPLAY_SPI_HOST SPI3_HOST +#define DISPLAY_SDA GPIO_NUM_10 +#define DISPLAY_SCL GPIO_NUM_9 +#define DISPLAY_DC GPIO_NUM_8 +#define DISPLAY_CS GPIO_NUM_14 +#define DISPLAY_RES GPIO_NUM_18 +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_13 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +// 电源管理 +#define POWER_USB_IN GPIO_NUM_1 +#define Power_Control GPIO_NUM_48 // 电源控制引脚 +#define Power_Dec GPIO_NUM_47 // 电源键检测引脚 +#define POWER_CBS_ADC_UNIT ADC_UNIT_1 // adc检测公共unit GPIO1 +#define POWER_USBIN_ADC_CHANNEL ADC_CHANNEL_0 // 检测usb是否插入 GPIO1 +#define POWER_BATTERY_ADC_CHANNEL ADC_CHANNEL_6 // 电池电量检测 GPIO7 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xingzhi-metal-1.54-wifi/config.json b/main/boards/xingzhi-metal-1.54-wifi/config.json new file mode 100644 index 0000000..53bebb5 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/config.json @@ -0,0 +1,10 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "xingzhi-metal-1.54-wifi", + "sdkconfig_append": [ + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/xingzhi-metal-1.54-wifi/cst816x.cc b/main/boards/xingzhi-metal-1.54-wifi/cst816x.cc new file mode 100644 index 0000000..4879c13 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/cst816x.cc @@ -0,0 +1,214 @@ +#include "cst816x.h" +#include "board.h" +#include "application.h" +#include "display.h" +#include "assets/lang_config.h" +// #include "audio_codec.h" +#include "wifi_board.h" +#include +#include "power_save_timer.h" +#include "codecs/es8311_audio_codec.h" +#include // 用于std::max/std::min + +#define TAG "Cst816x" + +const Cst816x::TouchThresholdConfig& Cst816x::getThresholdConfig(int x, int y) { + for (const auto& config : TOUCH_THRESHOLD_TABLE) { + if (config.x == x && config.y == y) { + return config; + } + } + return DEFAULT_THRESHOLD; +} + +Cst816x::Cst816x(i2c_master_bus_handle_t i2c_bus, uint8_t addr) : I2cDevice(i2c_bus, addr) { + uint8_t chip_id = ReadReg(0xA7); + ESP_LOGI(TAG, "Get CST816x chip ID: 0x%02X", chip_id); + read_buffer_ = new uint8_t[6]; +} + +Cst816x::~Cst816x() { + if (read_buffer_ != nullptr) { + delete[] read_buffer_; + read_buffer_ = nullptr; + } +} + +int64_t Cst816x::getCurrentTimeUs() { + struct timeval tv; + gettimeofday(&tv, nullptr); + return (int64_t)tv.tv_sec * 1000000L + tv.tv_usec; +} + +void Cst816x::UpdateTouchPoint() { + ReadRegs(0x02, read_buffer_, 6); + tp_.num = read_buffer_[0] & 0x0F; + tp_.x = ((read_buffer_[1] & 0x0F) << 8) | read_buffer_[2]; + tp_.y = ((read_buffer_[3] & 0x0F) << 8) | read_buffer_[4]; + memset(read_buffer_, 0, 6); +} + +void Cst816x::resetTouchCounters() { + is_touching_ = false; + touch_start_time_ = 0; + last_release_time_ = 0; + click_count_ = 0; + long_press_started_ = false; + + is_volume_long_pressing_ = false; + volume_long_press_dir_ = 0; + last_volume_adjust_time_ = 0; +} + +void Cst816x::touchpad_daemon(void* arg) { + Cst816x* cst816x = static_cast(arg); + auto& board = Board::GetInstance(); + auto codec = board.GetAudioCodec(); + auto display = board.GetDisplay(); + + while (1) { + cst816x->UpdateTouchPoint(); + auto& tp = cst816x->GetTouchPoint(); + int64_t current_time = cst816x->getCurrentTimeUs(); + + const auto& config = cst816x->getThresholdConfig(tp.x, tp.y); + if (tp.num > 0) { + ESP_LOGD(TAG, "Touch at (%d,%d) → SingleThresh:%lldms, DoubleWindow:%lldms, LongThresh:%lldms", + tp.x, tp.y, + config.single_click_thresh_us / 1000, + config.double_click_window_us / 1000, + config.long_press_thresh_us / 1000); + } + + TouchEvent current_event; + bool event_detected = false; + + if (tp.num > 0 && !cst816x->is_touching_) { + cst816x->is_touching_ = true; + cst816x->touch_start_time_ = current_time; + cst816x->long_press_started_ = false; + } + else if (tp.num > 0 && cst816x->is_touching_) { + if (!cst816x->long_press_started_ && + (current_time - cst816x->touch_start_time_ >= config.long_press_thresh_us)) { + current_event = {TouchEventType::LONG_PRESS_START, tp.x, tp.y}; + event_detected = true; + cst816x->long_press_started_ = true; + } + } + else if (tp.num == 0 && cst816x->is_touching_) { + cst816x->is_touching_ = false; + int64_t touch_duration = current_time - cst816x->touch_start_time_; + cst816x->last_release_time_ = current_time; + if (cst816x->long_press_started_) { + current_event = {TouchEventType::LONG_PRESS_END, tp.x, tp.y}; + event_detected = true; + } + else if (touch_duration <= config.single_click_thresh_us) { + cst816x->click_count_++; + } + } + else if (tp.num == 0 && !cst816x->is_touching_) { + if (cst816x->click_count_ > 0 && + (current_time - cst816x->last_release_time_ >= config.double_click_window_us)) { + if (cst816x->click_count_ == 2) { + current_event = {TouchEventType::DOUBLE_CLICK, tp.x, tp.y}; + event_detected = true; + } + else if (cst816x->click_count_ == 1) { + current_event = {TouchEventType::SINGLE_CLICK, tp.x, tp.y}; + event_detected = true; + } + cst816x->click_count_ = 0; + } + } + + if (event_detected) { + if (current_event.y == 600 && (current_event.x == 20 || current_event.x == 40 || current_event.x == 60)) { + switch (current_event.type) { + case TouchEventType::SINGLE_CLICK: + if (current_event.x == 40) { + board.SetPowerSaveMode(false); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + auto& wifi_board = static_cast(Board::GetInstance()); + wifi_board.ResetWifiConfiguration(); + } + app.ToggleChatState(); + } else if (current_event.x == 20) { // 20,600 单击:音量+ + int current_vol = codec->output_volume(); + int new_vol = current_vol + 10; + new_vol = (new_vol >= ES8311_VOL_MAX) ? ES8311_VOL_MAX : new_vol; + ESP_LOGI(TAG, "current_vol, new_vol(%d, %d)", current_vol, new_vol); + codec->EnableOutput(true); + codec->SetOutputVolume(new_vol); + display->ShowNotification(Lang::Strings::VOLUME + std::to_string(new_vol)); + } else if (current_event.x == 60) { // 60,600 单击:音量- + int current_vol = codec->output_volume(); + int new_vol = current_vol - 10; + new_vol = (new_vol <= ES8311_VOL_MIN) ? ES8311_VOL_MIN : new_vol; + ESP_LOGI(TAG, "current_vol, new_vol(%d, %d)", current_vol, new_vol); + codec->EnableOutput(true); + codec->SetOutputVolume(new_vol); + display->ShowNotification(Lang::Strings::VOLUME + std::to_string(new_vol)); + } + break; + + case TouchEventType::DOUBLE_CLICK: + ESP_LOGI(TAG, "Double click detected at (%d, %d)", current_event.x, current_event.y); + break; + + case TouchEventType::LONG_PRESS_START: + ESP_LOGI(TAG, "Long press started at (%d, %d) → Start volume adjust", current_event.x, current_event.y); + if (current_event.x == 20) { + cst816x->is_volume_long_pressing_ = true; + cst816x->volume_long_press_dir_ = 1; + cst816x->last_volume_adjust_time_ = current_time; + } else if (current_event.x == 60) { + cst816x->is_volume_long_pressing_ = true; + cst816x->volume_long_press_dir_ = -1; + cst816x->last_volume_adjust_time_ = current_time; + } + break; + + case TouchEventType::LONG_PRESS_END: + ESP_LOGI(TAG, "Long press ended at (%d, %d) → Stop volume adjust", current_event.x, current_event.y); + if (current_event.x == 20 || current_event.x == 60) { + cst816x->is_volume_long_pressing_ = false; + cst816x->volume_long_press_dir_ = 0; + cst816x->last_volume_adjust_time_ = 0; + } + break; + } + } + } + + if (cst816x->is_volume_long_pressing_) { + int64_t now = cst816x->getCurrentTimeUs(); + if (now - cst816x->last_volume_adjust_time_ >= cst816x->VOL_ADJ_INTERVAL_US) { + int current_vol = codec->output_volume(); + int new_vol = current_vol + (cst816x->volume_long_press_dir_ * cst816x->VOL_ADJ_STEP); + + new_vol = std::max(ES8311_VOL_MIN, std::min(ES8311_VOL_MAX, new_vol)); + + if (new_vol != current_vol) { + codec->EnableOutput(true); + codec->SetOutputVolume(new_vol); + display->ShowNotification(Lang::Strings::VOLUME + std::to_string(new_vol)); + cst816x->last_volume_adjust_time_ = now; + } else { + cst816x->is_volume_long_pressing_ = false; + cst816x->volume_long_press_dir_ = 0; + ESP_LOGI(TAG, "Volume reached limit (%d), stop adjusting", new_vol); + } + } + } + + vTaskDelay(pdMS_TO_TICKS(40)); + } +} + +void Cst816x::InitCst816d() { + ESP_LOGI(TAG, "Init CST816x touch driver"); + xTaskCreate(touchpad_daemon, "touch_daemon", 2048, this, 1, NULL); +} \ No newline at end of file diff --git a/main/boards/xingzhi-metal-1.54-wifi/cst816x.h b/main/boards/xingzhi-metal-1.54-wifi/cst816x.h new file mode 100644 index 0000000..7a8a3d3 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/cst816x.h @@ -0,0 +1,90 @@ +#ifndef _CST816X_H_ +#define _CST816X_H_ + +#include "esp_log.h" +#include "esp_err.h" +#include "driver/i2c.h" +#include "i2c_device.h" +#include +#include +#include + +#define ES8311_VOL_MIN 0 +#define ES8311_VOL_MAX 100 + +enum class TouchEventType { + SINGLE_CLICK, // 单击事件 + DOUBLE_CLICK, // 双击事件 + LONG_PRESS_START,// 长按开始事件 + LONG_PRESS_END // 长按结束事件 +}; + +struct TouchEvent { + TouchEventType type; + int x; + int y; +}; + +class Cst816x : public I2cDevice { +private: + struct TouchPoint_t { + int num = 0; + int x = -1; + int y = -1; + }; + + struct TouchThresholdConfig { + int x; // 目标X坐标 + int y; // 目标Y坐标 + int64_t single_click_thresh_us; // 单击最大时长(us) + int64_t double_click_window_us; // 双击窗口(us) + int64_t long_press_thresh_us; // 长按阈值(us) + }; + + const TouchThresholdConfig DEFAULT_THRESHOLD = { + .x = -1, .y = -1, + .single_click_thresh_us = 120000, // 150ms + .double_click_window_us = 240000, // 150ms + .long_press_thresh_us = 4000000 // 4000ms + }; + + const std::array TOUCH_THRESHOLD_TABLE = { + { + {20, 600, 200000, 240000, 2000000}, // 音量+ + {40, 600, 200000, 240000, 4000000}, // boot按键 + {60, 600, 200000, 240000, 2000000} // 音量- + } + }; + + const TouchThresholdConfig& getThresholdConfig(int x, int y); + + uint8_t* read_buffer_ = nullptr; + TouchPoint_t tp_; + + bool is_touching_ = false; + int64_t touch_start_time_ = 0; // 触摸开始时间(us) + int64_t last_release_time_ = 0; // 上次释放时间(us) + int click_count_ = 0; // 单击计数(双击检测用) + bool long_press_started_ = false; // 长按是否已触发 + + bool is_volume_long_pressing_ = false; // 是否处于音量长按调整中 + int volume_long_press_dir_ = 0; // 调整方向:1=递增,-1=递减 + int64_t last_volume_adjust_time_ = 0; // 上次调整音量的时间(us) + const int64_t VOL_ADJ_INTERVAL_US = 200000; // 音量调整间隔(100ms) + const int VOL_ADJ_STEP = 5; // 每次调整步长 + + int64_t getCurrentTimeUs(); + +public: + Cst816x(i2c_master_bus_handle_t i2c_bus, uint8_t addr); + ~Cst816x(); + + void InitCst816d(); + void UpdateTouchPoint(); + void resetTouchCounters(); + static void touchpad_daemon(void* param); + + const TouchPoint_t& GetTouchPoint() { return tp_; } +}; + +#endif \ No newline at end of file diff --git a/main/boards/xingzhi-metal-1.54-wifi/power_manager.h b/main/boards/xingzhi-metal-1.54-wifi/power_manager.h new file mode 100644 index 0000000..5be6ee8 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/power_manager.h @@ -0,0 +1,314 @@ +#pragma once +#include +#include + +#include +#include +#include +#include "sdkconfig.h" +#include "button.h" +#include "board.h" +#include "config.h" +#include "assets/lang_config.h" +#include + +class PowerManager { +private: + esp_timer_handle_t timer_handle_; + esp_timer_handle_t power_timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 30; + bool is_charging_ = false; + bool is_low_battery_ = false; + int ticks_ = 0; + adc_oneshot_unit_handle_t adc_handle_; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + + // power + bool pressed = false; // 是否按下电源键 + int PowerControl_ticks_ = 0; // 开机时长 + int press_ticks_ = 0; // 按下时的tick + bool is_first_boot = true; // + uint8_t PowerDec_level_ = 0; // 电源键电平 + const int power_off_ticks_ = 20; // 按键按下20/5秒准备关机; + bool new_charging_status = false; // 插入usb时无法软件关机 + bool is_shutting_down_ = false; // 标记是否进入关机流程 + int shutdown_delay_ticks_ = 0; // 关机延迟计数 + uint8_t shutdown_ticks = 5; // 5/5s后关机 预留的关机操作 + bool shutdown_first_ = true; + + // 旧版硬件软件关机逻辑 + void PowrSwitch() { + PowerDec_level_ = gpio_get_level(Power_Dec); + + // 确保开机后电源键松开再检测关机 + if (PowerDec_level_ == 1) { + is_first_boot = false; + } + + if (is_shutting_down_) { + shutdown_delay_ticks_++; + if (shutdown_delay_ticks_ >= shutdown_ticks) { + shutdown(); + is_shutting_down_ = false; + shutdown_delay_ticks_ = 0; + } + return; + } + + if (!is_first_boot) { + PowerControl_ticks_++; + if (PowerDec_level_ == 0 && pressed == false) { + press_ticks_ = PowerControl_ticks_; + pressed = true; + } + if ((press_ticks_ != 0) &&( PowerControl_ticks_ - press_ticks_ == power_off_ticks_ )&& (!new_charging_status)) { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + is_shutting_down_ = true; + shutdown_delay_ticks_ = 0; + } + if (PowerDec_level_ == 1 && press_ticks_!= 0) { + PowerDec_level_ = gpio_get_level(Power_Dec); + if (PowerDec_level_ == 1) { + pressed = false; + press_ticks_ = 0; + } + } + } + } + + void CheckBatteryStatus() { + int usb_usb_adc_value0; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, POWER_USBIN_ADC_CHANNEL, &usb_usb_adc_value0)); + new_charging_status = (1500 < usb_usb_adc_value0 && usb_usb_adc_value0 < 4000); + // ESP_LOGE("powercontrol", "USB ADC VALUE 1: %d", usb_usb_adc_value0); + + if (new_charging_status != is_charging_) { + ReadBatteryAdcData(); + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + } + + void ReadBatteryAdcData() { + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, POWER_BATTERY_ADC_CHANNEL, &adc_value)); + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += value; + } + average_adc /= adc_values_.size(); + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {1970, 0}, + {2062, 20}, + {2154, 40}, + {2246, 60}, + {2338, 80}, + {2430, 100} + }; + + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + + // Check low battery status + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + // 初始化电源键检测引脚 + gpio_config_t powerdecgpio_conf = {}; + powerdecgpio_conf.intr_type = GPIO_INTR_DISABLE; + powerdecgpio_conf.mode = GPIO_MODE_INPUT; + powerdecgpio_conf.pin_bit_mask = (1ULL << Power_Dec); + powerdecgpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + powerdecgpio_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&powerdecgpio_conf); + + // 初始化电源控制引脚 + gpio_config_t powercontgpio_conf = {}; + powercontgpio_conf.intr_type = GPIO_INTR_DISABLE; + powercontgpio_conf.mode = GPIO_MODE_OUTPUT; + powercontgpio_conf.pin_bit_mask = (1ULL << Power_Control); + powercontgpio_conf.pull_down_en = GPIO_PULLDOWN_ENABLE; + powercontgpio_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&powercontgpio_conf); + gpio_set_level(Power_Control, 1); + ESP_LOGI("powercontrol", "turnded on ..."); + + // 创建电源控制检查定时器 + esp_timer_create_args_t power_timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->PowrSwitch(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "power_cotrol_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&power_timer_args, &power_timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(power_timer_handle_, 200000)); + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = POWER_CBS_ADC_UNIT, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, POWER_BATTERY_ADC_CHANNEL, &chan_config)); // 电池电量 + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, POWER_USBIN_ADC_CHANNEL, &chan_config)); // usb + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (power_timer_handle_) { + esp_timer_stop(power_timer_handle_); + esp_timer_delete(power_timer_handle_); + } + if (adc_handle_ != nullptr) { + adc_oneshot_del_unit(adc_handle_); + } + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + uint8_t GetBatteryLevel() { + return battery_level_; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } + + void shutdown() { + if (!new_charging_status && shutdown_first_) + { + shutdown_first_ = false; // 进入后置 false ,防止再次进入关机状态 + gpio_config_t shutdown_gpio_conf = {}; + shutdown_gpio_conf.intr_type = GPIO_INTR_DISABLE; + shutdown_gpio_conf.mode = GPIO_MODE_OUTPUT; + shutdown_gpio_conf.pin_bit_mask = (1ULL << Power_Dec); + shutdown_gpio_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + shutdown_gpio_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&shutdown_gpio_conf); + gpio_set_level(DISPLAY_BACKLIGHT_PIN, 0); + gpio_set_level(Power_Control, 0); + for (int i=1;i<15;i++) { + gpio_set_level(Power_Dec, 1); + vTaskDelay(pdMS_TO_TICKS(100)); + gpio_set_level(Power_Dec, 0); + vTaskDelay(pdMS_TO_TICKS(100)); + ESP_LOGI("PowerManager","触发开关机控制"); + } + ESP_LOGI("PowerManager","关机失败,进入深睡眠"); + esp_deep_sleep_start(); + } else { + ESP_LOGI("PowerManager","检测到插入usb,无法关机"); + } + } +}; diff --git a/main/boards/xingzhi-metal-1.54-wifi/xingzhi-metal-1.54-wifi.cc b/main/boards/xingzhi-metal-1.54-wifi/xingzhi-metal-1.54-wifi.cc new file mode 100644 index 0000000..1ca4aa6 --- /dev/null +++ b/main/boards/xingzhi-metal-1.54-wifi/xingzhi-metal-1.54-wifi.cc @@ -0,0 +1,202 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "i2c_device.h" +#include +#include +#include +#include +#include "power_manager.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include +#include +#include +#include "cst816x.h" + +#define TAG "XINGZHI_METAL_1_54_WIFI" + +class XINGZHI_METAL_1_54_WIFI : public WifiBoard { +private: + i2c_master_bus_handle_t i2c_bus_; + Button boot_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + esp_err_t err; + bool is_device_found = false; + Cst816x *cst816d_; + + void InitializePowerManager() { + power_manager_ = new PowerManager(POWER_USB_IN);//USB是否插入 + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + ESP_LOGI(TAG, "Enabling sleep mode"); + display_->SetChatMessage("system", ""); + display_->SetEmotion("sleepy"); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + display_->SetChatMessage("system", ""); + display_->SetEmotion("neutral"); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + power_manager_->shutdown(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_)); + for (uint8_t addr = 1; addr < 127; addr++) { + err = i2c_master_probe(i2c_bus_, addr, 100); + if (err == ESP_OK) { + ESP_LOGI(TAG, "Device found at address 0x%02X", addr); + if (addr == 0x15) { + is_device_found = true; + } + } + } + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(DISPLAY_SPI_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeSt7789Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(DISPLAY_SPI_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, true)); + + display_ = new SpiLcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + } + + void Initialtouchtask() { + if (is_device_found) { + cst816d_ = new Cst816x(i2c_bus_, 0x15); + cst816d_->InitCst816d(); + } + } + +public: + XINGZHI_METAL_1_54_WIFI() : + boot_button_(BOOT_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeI2c(); + InitializeSpi(); + InitializeSt7789Display(); + Initialtouchtask(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec( + i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_I2C_PA_EN, + AUDIO_CODEC_ES8311_ADDR, + AUDIO_INPUT_REFERENCE); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + Cst816x *GetTouchpad() { + return cst816d_; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = power_manager_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XINGZHI_METAL_1_54_WIFI); diff --git a/main/boards/xmini-c3-4g/README.md b/main/boards/xmini-c3-4g/README.md new file mode 100644 index 0000000..9697085 --- /dev/null +++ b/main/boards/xmini-c3-4g/README.md @@ -0,0 +1,4 @@ +# 开源地址 + +https://oshwhub.com/tenclass01/xmini_c3_4g + diff --git a/main/boards/xmini-c3-4g/config.h b/main/boards/xmini-c3-4g/config.h new file mode 100644 index 0000000..8a38e0f --- /dev/null +++ b/main/boards/xmini-c3-4g/config.h @@ -0,0 +1,32 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_7 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_5 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_8 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_13 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_21 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_20 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_3 +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#define ML307_TX_PIN GPIO_NUM_2 +#define ML307_RX_PIN GPIO_NUM_0 +#define ML307_DTR_PIN GPIO_NUM_1 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xmini-c3-4g/config.json b/main/boards/xmini-c3-4g/config.json new file mode 100644 index 0000000..b17fde6 --- /dev/null +++ b/main/boards/xmini-c3-4g/config.json @@ -0,0 +1,15 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "xmini-c3-4g", + "sdkconfig_append": [ + "CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y", + "CONFIG_PARTITION_TABLE_CUSTOM_FILENAME=\"partitions/v2/8m.csv\"", + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/xmini-c3-4g/xmini_c3_4g_board.cc b/main/boards/xmini-c3-4g/xmini_c3_4g_board.cc new file mode 100644 index 0000000..c89a0cb --- /dev/null +++ b/main/boards/xmini-c3-4g/xmini_c3_4g_board.cc @@ -0,0 +1,204 @@ +#include "ml307_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/oled_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "settings.h" +#include "config.h" +#include "sleep_timer.h" +#include "adc_battery_monitor.h" +#include "press_to_talk_mcp_tool.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "XminiC3Board" + +class XminiC3Board : public Ml307Board { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + SleepTimer* sleep_timer_ = nullptr; + AdcBatteryMonitor* adc_battery_monitor_ = nullptr; + PressToTalkMcpTool* press_to_talk_tool_ = nullptr; + + void InitializeBatteryMonitor() { + adc_battery_monitor_ = new AdcBatteryMonitor(ADC_UNIT_1, ADC_CHANNEL_4, 100000, 100000, GPIO_NUM_12); + adc_battery_monitor_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + sleep_timer_->SetEnabled(false); + } else { + sleep_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + // Wake word detection will be disabled in light sleep mode + sleep_timer_ = new SleepTimer(30); + sleep_timer_->OnEnterLightSleepMode([this]() { + ESP_LOGI(TAG, "Enabling sleep mode"); + // Show the standby screen + GetDisplay()->SetPowerSaveMode(true); + // Enable sleep mode, and sleep in 1 second after DTR is set to high + modem_->SetSleepMode(true, 1); + // Set the DTR pin to high to make the modem enter sleep mode + modem_->GetAtUart()->SetDtrPin(true); + }); + sleep_timer_->OnExitLightSleepMode([this]() { + // Set the DTR pin to low to make the modem wake up + modem_->GetAtUart()->SetDtrPin(false); + // Hide the standby screen + GetDisplay()->SetPowerSaveMode(false); + }); + sleep_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(codec_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (!press_to_talk_tool_ || !press_to_talk_tool_->IsPressToTalkEnabled()) { + app.ToggleChatState(); + } + }); + boot_button_.OnPressDown([this]() { + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StartListening(); + } + }); + boot_button_.OnPressUp([this]() { + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StopListening(); + } + }); + } + + void InitializeTools() { + press_to_talk_tool_ = new PressToTalkMcpTool(); + press_to_talk_tool_->Initialize(); + } + +public: + XminiC3Board() : Ml307Board(ML307_TX_PIN, ML307_RX_PIN, ML307_DTR_PIN), + boot_button_(BOOT_BUTTON_GPIO, false, 0, 0, true) { + + InitializeBatteryMonitor(); + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + charging = adc_battery_monitor_->IsCharging(); + discharging = adc_battery_monitor_->IsDischarging(); + level = adc_battery_monitor_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + sleep_timer_->WakeUp(); + } + Ml307Board::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XminiC3Board); diff --git a/main/boards/xmini-c3-v3/README.md b/main/boards/xmini-c3-v3/README.md new file mode 100644 index 0000000..87dfd43 --- /dev/null +++ b/main/boards/xmini-c3-v3/README.md @@ -0,0 +1,4 @@ +# 开源地址 + +https://oshwhub.com/tenclass01/xmini_c3 + diff --git a/main/boards/xmini-c3-v3/config.h b/main/boards/xmini-c3-v3/config.h new file mode 100644 index 0000000..1f75de6 --- /dev/null +++ b/main/boards/xmini-c3-v3/config.h @@ -0,0 +1,28 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_5 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_4 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_10 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_0 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_1 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_2 +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xmini-c3-v3/config.json b/main/boards/xmini-c3-v3/config.json new file mode 100644 index 0000000..e830af0 --- /dev/null +++ b/main/boards/xmini-c3-v3/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "xmini-c3-v3", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_USE_ESP_WAKE_WORD=y", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/xmini-c3-v3/xmini_c3_board.cc b/main/boards/xmini-c3-v3/xmini_c3_board.cc new file mode 100644 index 0000000..2462ad0 --- /dev/null +++ b/main/boards/xmini-c3-v3/xmini_c3_board.cc @@ -0,0 +1,199 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/oled_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "settings.h" +#include "config.h" +#include "power_save_timer.h" +#include "adc_battery_monitor.h" +#include "press_to_talk_mcp_tool.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "XminiC3Board" + +class XminiC3Board : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + PowerSaveTimer* power_save_timer_ = nullptr; + AdcBatteryMonitor* adc_battery_monitor_ = nullptr; + PressToTalkMcpTool* press_to_talk_tool_ = nullptr; + + void InitializePowerManager() { + adc_battery_monitor_ = new AdcBatteryMonitor(ADC_UNIT_1, ADC_CHANNEL_3, 100000, 100000, GPIO_NUM_12); + adc_battery_monitor_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(160, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(codec_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + if (!press_to_talk_tool_ || !press_to_talk_tool_->IsPressToTalkEnabled()) { + app.ToggleChatState(); + } + }); + boot_button_.OnPressDown([this]() { + if (power_save_timer_) { + power_save_timer_->WakeUp(); + } + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StartListening(); + } + }); + boot_button_.OnPressUp([this]() { + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StopListening(); + } + }); + } + + void InitializeTools() { + press_to_talk_tool_ = new PressToTalkMcpTool(); + press_to_talk_tool_->Initialize(); + } + +public: + XminiC3Board() : boot_button_(BOOT_BUTTON_GPIO, false, 0, 0, true) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeCodecI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializeTools(); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + charging = adc_battery_monitor_->IsCharging(); + discharging = adc_battery_monitor_->IsDischarging(); + level = adc_battery_monitor_->GetBatteryLevel(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XminiC3Board); diff --git a/main/boards/xmini-c3/config.h b/main/boards/xmini-c3/config.h new file mode 100644 index 0000000..f37a035 --- /dev/null +++ b/main/boards/xmini-c3/config.h @@ -0,0 +1,28 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_10 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_6 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_8 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_7 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_5 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_11 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_3 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_4 +#define AUDIO_CODEC_ES8311_ADDR ES8311_CODEC_DEFAULT_ADDR + +#define BUILTIN_LED_GPIO GPIO_NUM_2 +#define BOOT_BUTTON_GPIO GPIO_NUM_9 + +#define DISPLAY_WIDTH 128 +#define DISPLAY_HEIGHT 64 +#define DISPLAY_MIRROR_X true +#define DISPLAY_MIRROR_Y true + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/xmini-c3/config.json b/main/boards/xmini-c3/config.json new file mode 100644 index 0000000..0073568 --- /dev/null +++ b/main/boards/xmini-c3/config.json @@ -0,0 +1,14 @@ +{ + "target": "esp32c3", + "builds": [ + { + "name": "xmini-c3", + "sdkconfig_append": [ + "CONFIG_PM_ENABLE=y", + "CONFIG_FREERTOS_USE_TICKLESS_IDLE=y", + "CONFIG_USE_ESP_WAKE_WORD=y", + "CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/xmini-c3/xmini_c3_board.cc b/main/boards/xmini-c3/xmini_c3_board.cc new file mode 100644 index 0000000..4707d85 --- /dev/null +++ b/main/boards/xmini-c3/xmini_c3_board.cc @@ -0,0 +1,182 @@ +#include "wifi_board.h" +#include "codecs/es8311_audio_codec.h" +#include "display/oled_display.h" +#include "application.h" +#include "button.h" +#include "led/single_led.h" +#include "mcp_server.h" +#include "settings.h" +#include "config.h" +#include "power_save_timer.h" +#include "press_to_talk_mcp_tool.h" + +#include +#include +#include +#include +#include +#include + +#define TAG "XminiC3Board" + +class XminiC3Board : public WifiBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + Display* display_ = nullptr; + Button boot_button_; + PowerSaveTimer* power_save_timer_ = nullptr; + PressToTalkMcpTool* press_to_talk_tool_ = nullptr; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(160, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeCodecI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + + // Print I2C bus info + if (i2c_master_probe(codec_i2c_bus_, 0x18, 1000) != ESP_OK) { + while (true) { + ESP_LOGE(TAG, "Failed to probe I2C bus, please check if you have installed the correct firmware"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + } + } + + void InitializeSsd1306Display() { + // SSD1306 config + esp_lcd_panel_io_i2c_config_t io_config = { + .dev_addr = 0x3C, + .on_color_trans_done = nullptr, + .user_ctx = nullptr, + .control_phase_bytes = 1, + .dc_bit_offset = 6, + .lcd_cmd_bits = 8, + .lcd_param_bits = 8, + .flags = { + .dc_low_on_data = 0, + .disable_control_phase = 0, + }, + .scl_speed_hz = 400 * 1000, + }; + + ESP_ERROR_CHECK(esp_lcd_new_panel_io_i2c_v2(codec_i2c_bus_, &io_config, &panel_io_)); + + ESP_LOGI(TAG, "Install SSD1306 driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = -1; + panel_config.bits_per_pixel = 1; + + esp_lcd_panel_ssd1306_config_t ssd1306_config = { + .height = static_cast(DISPLAY_HEIGHT), + }; + panel_config.vendor_config = &ssd1306_config; + + ESP_ERROR_CHECK(esp_lcd_new_panel_ssd1306(panel_io_, &panel_config, &panel_)); + ESP_LOGI(TAG, "SSD1306 driver installed"); + + // Reset the display + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + if (esp_lcd_panel_init(panel_) != ESP_OK) { + ESP_LOGE(TAG, "Failed to initialize display"); + display_ = new NoDisplay(); + return; + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel_, true)); + + display_ = new OledDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + if (!press_to_talk_tool_ || !press_to_talk_tool_->IsPressToTalkEnabled()) { + app.ToggleChatState(); + } + }); + boot_button_.OnPressDown([this]() { + if (power_save_timer_) { + power_save_timer_->WakeUp(); + } + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StartListening(); + } + }); + boot_button_.OnPressUp([this]() { + if (press_to_talk_tool_ && press_to_talk_tool_->IsPressToTalkEnabled()) { + Application::GetInstance().StopListening(); + } + }); + } + + void InitializeTools() { + press_to_talk_tool_ = new PressToTalkMcpTool(); + press_to_talk_tool_->Initialize(); + } + +public: + XminiC3Board() : boot_button_(BOOT_BUTTON_GPIO) { + InitializeCodecI2c(); + InitializeSsd1306Display(); + InitializeButtons(); + InitializePowerSaveTimer(); + InitializeTools(); + + // 避免使用错误的固件,把 EFUSE 操作放在最后 + // 把 ESP32C3 的 VDD SPI 引脚作为普通 GPIO 口使用 + esp_efuse_write_field_bit(ESP_EFUSE_VDD_SPI_AS_GPIO); + } + + virtual Led* GetLed() override { + static SingleLed led(BUILTIN_LED_GPIO); + return &led; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8311AudioCodec audio_codec(codec_i2c_bus_, I2C_NUM_0, AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, AUDIO_I2S_GPIO_BCLK, AUDIO_I2S_GPIO_WS, AUDIO_I2S_GPIO_DOUT, AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, AUDIO_CODEC_ES8311_ADDR); + return &audio_codec; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(XminiC3Board); diff --git a/main/boards/yunliao-s3/README.md b/main/boards/yunliao-s3/README.md new file mode 100644 index 0000000..011cc54 --- /dev/null +++ b/main/boards/yunliao-s3/README.md @@ -0,0 +1,88 @@ +# 小智云聊S3 + +## 简介 +小智云聊S3是小智AI的魔改项目,是首个2.8寸护眼大屏+大字体+2000mah大电池的量产成品,做了大量创新和优化。 + +## 合并版 +合并版代码在小智AI主项目中维护,跟随主项目的一起版本更新,便于用户自行扩展和第三方固件扩展。支持语音唤醒、语音打断、OTA、4G自由切换等功能。 + +>### 按键操作 +>- **开机**: 关机状态,长按1秒后释放按键,自动开机 +>- **关机**: 开机状态,长按1秒后释放按键,标题栏会显示'请稍候',再等2秒自动关机 +>- **唤醒/打断**: 正常通话环境下,单击按键 +>- **切换4G/Wifi**: 启动过程或者配网界面,1秒钟内双击按键(需安装4G模块) +>- **重新配网**: 开机状态,1秒钟内三击按键,会自动重启并进入配网界面 + +## 魔改版 +魔改版由于底层改动太大,代码单独维护,定期合并主项目代码。 + +>### 为什么是魔改 +>- 首个实现微信二维码配网。 +>- 首个支持单手机配网。 +>- 首个支持扫二维码访问控制台。 +>- 首发支持繁体、日文、英文版界面 +>- 首个全语音操控模式 +>- 独家提供一键刷机脚本等多种刷机方式 + +## 版本区别 +>| 特性 | 合并版 | 魔改版 | +>| --- | --- | --- | +>| 语音打断 | ✓ | ✓ | +>| 4G功能 | ✓ | ✓ | +>| 自动更新固件 | ✓ | X | +>| 第三方固件支持 | ✓ | X | +>| 天气待机界面 | X | ✓ | +>| 闹钟提醒 | X | ✓ | +>| 网络音乐播放 | X | ✓ | +>| 微信扫码配网 | X | ✓ | +>| 单手机配网 | X | ✓ | +>| 扫码访问控制台 | X | ✓ | +>| 繁日英文界面 | X | ✓ | +>| 多语言支持 | X | ✓ | +>| 外接蓝牙音箱 | X | ✓ | + + +# 编译配置命令 + +**克隆工程** + +```bash +git clone https://github.com/78/xiaozhi-esp32.git +``` + +**进入工程** + +```bash +cd xiaozhi-esp32 +``` + +**配置编译目标为 ESP32S3** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig** + +```bash +idf.py menuconfig +``` + +**选择板子** + +```bash +- `Xiaozhi Assistant` → `Board Type` → 选择 `小智云聊-S3` → 选择 `Enable Device-Side AEC` +``` + +**编译** + +```ba +idf.py build +``` + +**下载并打开串口终端** + +```bash +idf.py build flash monitor +``` + diff --git a/main/boards/yunliao-s3/config.h b/main/boards/yunliao-s3/config.h new file mode 100644 index 0000000..be74002 --- /dev/null +++ b/main/boards/yunliao-s3/config.h @@ -0,0 +1,59 @@ +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_REFERENCE true + +#define AUDIO_INPUT_SAMPLE_RATE 24000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_DEFAULT_OUTPUT_VOLUME 70 + +#define AUDIO_I2S_GPIO_MCLK GPIO_NUM_14 +#define AUDIO_I2S_GPIO_BCLK GPIO_NUM_13 +#define AUDIO_I2S_GPIO_WS GPIO_NUM_11 +#define AUDIO_I2S_GPIO_DOUT GPIO_NUM_12 +#define AUDIO_I2S_GPIO_DIN GPIO_NUM_10 + +#define AUDIO_CODEC_PA_PIN GPIO_NUM_17 +#define AUDIO_CODEC_I2C_SCL_PIN GPIO_NUM_21 +#define AUDIO_CODEC_I2C_SDA_PIN GPIO_NUM_18 +#define AUDIO_CODEC_ES8388_ADDR ES8388_CODEC_DEFAULT_ADDR + +#define BOOT_BUTTON_PIN GPIO_NUM_2 +#define BOOT_5V_PIN GPIO_NUM_3 //5V升压输出 +#define BOOT_4G_PIN GPIO_NUM_5 //4G模块使能 +#define MON_BATT_PIN GPIO_NUM_43 //检测PMU电池指示 +#define MON_BATT_CNT 70 //检测PMU电池秒数 +#define MON_USB_PIN GPIO_NUM_47 //检测USB插入 + + +#define ML307_RX_PIN GPIO_NUM_16 +#define ML307_TX_PIN GPIO_NUM_15 + +#define DISPLAY_SPI_LCD_HOST SPI2_HOST +#define DISPLAY_SPI_CLOCK_HZ (40 * 1000 * 1000) +#define DISPLAY_SPI_PIN_SCLK 42 +#define DISPLAY_SPI_PIN_MOSI 40 +#define DISPLAY_SPI_PIN_MISO -1 +#define DISPLAY_SPI_PIN_LCD_DC 41 +#define DISPLAY_SPI_PIN_LCD_RST 45 +#define DISPLAY_SPI_PIN_LCD_CS -1 +#define DISPLAY_PIN_TOUCH_CS -1 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_46 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define DISPLAY_WIDTH 320 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY true +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y true +#define DISPLAY_INVERT_COLOR false +#define DISPLAY_RGB_ORDER_COLOR LCD_RGB_ELEMENT_ORDER_RGB + +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 +#define KEY_EXPIRE_MS 800 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/yunliao-s3/config.json b/main/boards/yunliao-s3/config.json new file mode 100644 index 0000000..1261a68 --- /dev/null +++ b/main/boards/yunliao-s3/config.json @@ -0,0 +1,11 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "yunliao-s3", + "sdkconfig_append": [ + "CONFIG_USE_DEVICE_AEC=y" + ] + } + ] +} \ No newline at end of file diff --git a/main/boards/yunliao-s3/power_manager.cc b/main/boards/yunliao-s3/power_manager.cc new file mode 100644 index 0000000..6a8ef74 --- /dev/null +++ b/main/boards/yunliao-s3/power_manager.cc @@ -0,0 +1,203 @@ +#include "power_manager.h" +#include "esp_sleep.h" +#include "driver/rtc_io.h" +#include "esp_log.h" +#include "config.h" +#include +#include "esp_log.h" +#include "settings.h" + +#define TAG "PowerManager" + +static QueueHandle_t gpio_evt_queue = NULL; +uint16_t battCnt;//闪灯次数 +int battLife = 70; //电量 + +// 中断服务程序 +static void IRAM_ATTR batt_mon_isr_handler(void* arg) { + uint32_t gpio_num = (uint32_t) arg; + xQueueSendFromISR(gpio_evt_queue, &gpio_num, NULL); +} + +// 添加任务处理函数 +static void batt_mon_task(void* arg) { + uint32_t io_num; + while(1) { + if(xQueueReceive(gpio_evt_queue, &io_num, portMAX_DELAY)) { + battCnt++; + } + } +} + +static void calBattLife() { + // 计算电量 + battLife = battCnt; + + if (battLife > 100){ + battLife = 100; + } + // ESP_LOGI(TAG, "Battery life:%d", (int)battLife); + // 重置计数器 + battCnt = 0; +} + +PowerManager::PowerManager(){ +} + +void PowerManager::Initialize(){ + // 初始化5V控制引脚 + gpio_config_t io_conf_5v = { + .pin_bit_mask = 1<(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); +} + +void PowerManager::CheckBatteryStatus(){ + call_count_++; + if(call_count_ >= MON_BATT_CNT) { + calBattLife(); + call_count_ = 0; + } + + bool new_charging_status = IsCharging(); + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (charging_callback_) { + charging_callback_(is_charging_); + } + } + + bool new_discharging_status = IsDischarging(); + if (new_discharging_status != is_discharging_) { + is_discharging_ = new_discharging_status; + if (discharging_callback_) { + discharging_callback_(is_discharging_); + } + } +} + +bool PowerManager::IsCharging() { + return gpio_get_level(MON_USB_PIN) == 1 && !IsChargingDone(); +} + +bool PowerManager::IsDischarging() { + return gpio_get_level(MON_USB_PIN) == 0; +} + +bool PowerManager::IsChargingDone() { + return battLife >= 95; +} + +int PowerManager::GetBatteryLevel() { + return battLife; +} + +void PowerManager::OnChargingStatusChanged(std::function callback) { + charging_callback_ = callback; +} + +void PowerManager::OnChargingStatusDisChanged(std::function callback) { + discharging_callback_ = callback; +} + +void PowerManager::CheckStartup() { + Settings settings1("board", true); + if(settings1.GetInt("sleep_flag", 0) > 0){ + vTaskDelay(pdMS_TO_TICKS(1000)); + if( gpio_get_level(BOOT_BUTTON_PIN) == 1) { + Sleep(); //进入休眠模式 + }else{ + settings1.SetInt("sleep_flag", 0); + } + } +} + +void PowerManager::Start5V() { + gpio_set_level(BOOT_5V_PIN, 1); +} + +void PowerManager::Shutdown5V() { + gpio_set_level(BOOT_5V_PIN, 0); +} + +void PowerManager::Start4G() { + gpio_set_level(BOOT_4G_PIN, 1); +} + +void PowerManager::Shutdown4G() { + gpio_set_level(BOOT_4G_PIN, 0); + gpio_set_level(ML307_RX_PIN,1); + gpio_set_level(ML307_TX_PIN,1); +} + +void PowerManager::Sleep() { + ESP_LOGI(TAG, "Entering deep sleep"); + Settings settings("board", true); + settings.SetInt("sleep_flag", 1); + Shutdown4G(); + Shutdown5V(); + + if(gpio_evt_queue) { + vQueueDelete(gpio_evt_queue); + gpio_evt_queue = NULL; + } + ESP_ERROR_CHECK(gpio_isr_handler_remove(BOOT_BUTTON_PIN)); + ESP_ERROR_CHECK(esp_sleep_enable_ext0_wakeup(BOOT_BUTTON_PIN, 0)); + ESP_ERROR_CHECK(rtc_gpio_pulldown_dis(BOOT_BUTTON_PIN)); + ESP_ERROR_CHECK(rtc_gpio_pullup_en(BOOT_BUTTON_PIN)); + esp_deep_sleep_start(); +} \ No newline at end of file diff --git a/main/boards/yunliao-s3/power_manager.h b/main/boards/yunliao-s3/power_manager.h new file mode 100644 index 0000000..921cf47 --- /dev/null +++ b/main/boards/yunliao-s3/power_manager.h @@ -0,0 +1,37 @@ +#ifndef __POWERMANAGER_H__ +#define __POWERMANAGER_H__ + +#include +#include "driver/gpio.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "freertos/queue.h" +#include "freertos/timers.h" + +class PowerManager{ +public: + PowerManager(); + void Initialize(); + bool IsCharging(); + bool IsDischarging(); + bool IsChargingDone(); + int GetBatteryLevel(); + void CheckStartup(); + void Start5V(); + void Shutdown5V(); + void Start4G(); + void Shutdown4G(); + void Sleep(); + void CheckBatteryStatus(); + void OnChargingStatusChanged(std::function callback); + void OnChargingStatusDisChanged(std::function callback); +private: + esp_timer_handle_t timer_handle_; + std::function charging_callback_; + std::function discharging_callback_; + int is_charging_ = -1; + int is_discharging_ = -1; + int call_count_ = 0; +}; + +#endif \ No newline at end of file diff --git a/main/boards/yunliao-s3/yunliao_s3.cc b/main/boards/yunliao-s3/yunliao_s3.cc new file mode 100644 index 0000000..f50ed64 --- /dev/null +++ b/main/boards/yunliao-s3/yunliao_s3.cc @@ -0,0 +1,212 @@ +#include "lvgl_theme.h" +#include "dual_network_board.h" +#include "codecs/es8388_audio_codec.h" +#include "display/lcd_display.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "power_manager.h" +#include "assets/lang_config.h" +#include +#include +#include + + +#define TAG "YunliaoS3" + +class YunliaoS3 : public DualNetworkBoard { +private: + i2c_master_bus_handle_t codec_i2c_bus_; + Button boot_button_; + SpiLcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + + void InitializePowerSaveTimer() { + power_save_timer_ = new PowerSaveTimer(-1, 60, 600); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(10); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->OnShutdownRequest([this]() { + ESP_LOGI(TAG, "Shutting down"); + power_manager_->Sleep(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeI2c() { + // Initialize I2C peripheral + i2c_master_bus_config_t i2c_bus_cfg = { + .i2c_port = I2C_NUM_0, + .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN, + .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN, + .clk_source = I2C_CLK_SRC_DEFAULT, + .glitch_ignore_cnt = 7, + .intr_priority = 0, + .trans_queue_depth = 0, + .flags = { + .enable_internal_pullup = 1, + }, + }; + ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &codec_i2c_bus_)); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SPI_PIN_MOSI; + buscfg.miso_io_num = DISPLAY_SPI_PIN_MISO; + buscfg.sclk_io_num = DISPLAY_SPI_PIN_SCLK; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(DISPLAY_SPI_LCD_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + app.ToggleChatState(); + }); + boot_button_.OnDoubleClick([this]() { + ESP_LOGI(TAG, "Button OnDoubleClick"); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting || app.GetDeviceState() == kDeviceStateWifiConfiguring) { + SwitchNetworkType(); + } + }); + boot_button_.OnMultipleClick([this]() { + ESP_LOGI(TAG, "Button OnThreeClick"); + if (GetNetworkType() == NetworkType::WIFI) { + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + },3); + boot_button_.OnLongPress([this]() { + ESP_LOGI(TAG, "Button LongPress to Sleep"); + display_->SetStatus(Lang::Strings::PLEASE_WAIT); + vTaskDelay(pdMS_TO_TICKS(2000)); + power_manager_->Sleep(); + }); + } + void InitializeSt7789Display() { + esp_lcd_panel_io_handle_t panel_io = nullptr; + esp_lcd_panel_handle_t panel = nullptr; + // 液晶屏控制IO初始化 + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_SPI_PIN_LCD_CS; + io_config.dc_gpio_num = DISPLAY_SPI_PIN_LCD_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = DISPLAY_SPI_CLOCK_HZ; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(DISPLAY_SPI_LCD_HOST, &io_config, &panel_io)); + + // 初始化液晶屏驱动芯片ST7789 + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_SPI_PIN_LCD_RST; + panel_config.rgb_ele_order = DISPLAY_RGB_ORDER_COLOR; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io, &panel_config, &panel)); + + esp_lcd_panel_reset(panel); + esp_lcd_panel_init(panel); + esp_lcd_panel_invert_color(panel, DISPLAY_INVERT_COLOR); + esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY); + esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y); + display_ = new SpiLcdDisplay(panel_io, panel, DISPLAY_WIDTH, + DISPLAY_HEIGHT, DISPLAY_OFFSET_X, + DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, + DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + auto& theme_manager = LvglThemeManager::GetInstance(); + auto theme = theme_manager.GetTheme("dark"); + if (theme != nullptr) { + display_->SetTheme(theme); + } + } + +public: + YunliaoS3() : + DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN, GPIO_NUM_NC, 0), + boot_button_(BOOT_BUTTON_PIN), + power_manager_(new PowerManager()){ + power_manager_->Start5V(); + power_manager_->Initialize(); + InitializeI2c(); + power_manager_->CheckStartup(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeSt7789Display(); + power_manager_->OnChargingStatusDisChanged([this](bool is_discharging) { + if(power_save_timer_){ + if (is_discharging) { + power_save_timer_->SetEnabled(true); + } else { + power_save_timer_->SetEnabled(false); + } + } + }); + if(GetNetworkType() == NetworkType::WIFI){ + power_manager_->Shutdown4G(); + }else{ + power_manager_->Start4G(); + } + GetBacklight()->RestoreBrightness(); + while(gpio_get_level(BOOT_BUTTON_PIN) == 0){ + vTaskDelay(pdMS_TO_TICKS(10)); + } + InitializeButtons(); + } + + virtual AudioCodec* GetAudioCodec() override { + static Es8388AudioCodec audio_codec( + codec_i2c_bus_, + I2C_NUM_0, + AUDIO_INPUT_SAMPLE_RATE, + AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_GPIO_MCLK, + AUDIO_I2S_GPIO_BCLK, + AUDIO_I2S_GPIO_WS, + AUDIO_I2S_GPIO_DOUT, + AUDIO_I2S_GPIO_DIN, + AUDIO_CODEC_PA_PIN, + AUDIO_CODEC_ES8388_ADDR, + AUDIO_INPUT_REFERENCE + ); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + level = power_manager_->GetBatteryLevel(); + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(YunliaoS3); diff --git a/main/boards/zhengchen-1.54tft-ml307/README.md b/main/boards/zhengchen-1.54tft-ml307/README.md new file mode 100644 index 0000000..a7f289b --- /dev/null +++ b/main/boards/zhengchen-1.54tft-ml307/README.md @@ -0,0 +1,45 @@ +# 产品相关介绍网址 + +```http +https://e.tb.cn/h.6Gl2LC7rsrswQZp?tk=qFuaV9hzh0k CZ356 +``` + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> zhengchen-1.54tft-ml307 +``` + +``` + +**编译:** + +bash +idf.py build +``` + +**下载:** +idf.py build flash monitor + +进行下载和显示日志 + + +**固件生成:** + +```bash +idf.py merge-bin +``` diff --git a/main/boards/zhengchen-1.54tft-ml307/config.h b/main/boards/zhengchen-1.54tft-ml307/config.h new file mode 100644 index 0000000..888a052 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-ml307/config.h @@ -0,0 +1,42 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 + +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_10 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA GPIO_NUM_41 +#define DISPLAY_SCL GPIO_NUM_42 +#define DISPLAY_RES GPIO_NUM_45 +#define DISPLAY_DC GPIO_NUM_40 +#define DISPLAY_CS GPIO_NUM_21 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + +#define ML307_RX_PIN GPIO_NUM_11 +#define ML307_TX_PIN GPIO_NUM_12 + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/zhengchen-1.54tft-ml307/config.json b/main/boards/zhengchen-1.54tft-ml307/config.json new file mode 100644 index 0000000..6e17be7 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-ml307/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "zhengchen-1.54tft-ml307", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/zhengchen-1.54tft-ml307/zhengchen-1.54tft-ml307.cc b/main/boards/zhengchen-1.54tft-ml307/zhengchen-1.54tft-ml307.cc new file mode 100644 index 0000000..48845a1 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-ml307/zhengchen-1.54tft-ml307.cc @@ -0,0 +1,211 @@ +#include "dual_network_board.h" +#include "codecs/no_audio_codec.h" +#include "../zhengchen-1.54tft-wifi/zhengchen_lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "../zhengchen-1.54tft-wifi/power_manager.h" + +#include +#include +#include + +#include +#include + +#define TAG "ZHENGCHEN_1_54TFT_ML307" + +class ZHENGCHEN_1_54TFT_ML307 : public DualNetworkBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + ZHENGCHEN_LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_9); + power_manager_->OnTemperatureChanged([this](float chip_temp) { + display_->UpdateHighTempWarning(chip_temp); + }); + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + } else { + power_save_timer_->SetEnabled(true); + } + }); + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_2); + rtc_gpio_set_direction(GPIO_NUM_2, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_2, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (GetNetworkType() == NetworkType::WIFI) { + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + // cast to WifiBoard + auto& wifi_board = static_cast(GetCurrentBoard()); + wifi_board.ResetWifiConfiguration(); + } + } + app.ToggleChatState(); + }); + + boot_button_.OnLongPress([this]() { + SwitchNetworkType(); + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume/10)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume/10)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, true)); + + display_ = new ZHENGCHEN_LcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + display_->SetupHighTempWarningPopup(); + } + +public: + ZHENGCHEN_1_54TFT_ML307() : + DualNetworkBoard(ML307_TX_PIN, ML307_RX_PIN), + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + GetBacklight()->RestoreBrightness(); + } + + virtual AudioCodec* GetAudioCodec() override { + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = std::max(power_manager_->GetBatteryLevel(), 20); + return true; + } + + virtual bool GetTemperature(float& esp32temp) override { + esp32temp = power_manager_->GetTemperature(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + DualNetworkBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(ZHENGCHEN_1_54TFT_ML307); diff --git a/main/boards/zhengchen-1.54tft-wifi/README.md b/main/boards/zhengchen-1.54tft-wifi/README.md new file mode 100644 index 0000000..20bd9a6 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/README.md @@ -0,0 +1,45 @@ +# 产品相关介绍网址 + +```http +https://e.tb.cn/h.6Gl2LC7rsrswQZp?tk=qFuaV9hzh0k CZ356 +``` + +# 编译配置命令 + +**配置编译目标为 ESP32S3:** + +```bash +idf.py set-target esp32s3 +``` + +**打开 menuconfig:** + +```bash +idf.py menuconfig +``` + +**选择板子:** + +``` +Xiaozhi Assistant -> Board Type -> zhengchen-1.54tft-wifi +``` + +``` + +**编译:** + +bash +idf.py build +``` + +**下载:** +idf.py build flash monitor + +进行下载和显示日志 + + +**固件生成:** + +```bash +idf.py merge-bin +``` diff --git a/main/boards/zhengchen-1.54tft-wifi/config.h b/main/boards/zhengchen-1.54tft-wifi/config.h new file mode 100644 index 0000000..f7d971a --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/config.h @@ -0,0 +1,39 @@ + +#ifndef _BOARD_CONFIG_H_ +#define _BOARD_CONFIG_H_ + +#include + +#define AUDIO_INPUT_SAMPLE_RATE 16000 +#define AUDIO_OUTPUT_SAMPLE_RATE 24000 +#define AUDIO_I2S_MIC_GPIO_WS GPIO_NUM_4 +#define AUDIO_I2S_MIC_GPIO_SCK GPIO_NUM_5 +#define AUDIO_I2S_MIC_GPIO_DIN GPIO_NUM_6 +#define AUDIO_I2S_SPK_GPIO_DOUT GPIO_NUM_7 +#define AUDIO_I2S_SPK_GPIO_BCLK GPIO_NUM_15 +#define AUDIO_I2S_SPK_GPIO_LRCK GPIO_NUM_16 + +#define BOOT_BUTTON_GPIO GPIO_NUM_0 +#define VOLUME_UP_BUTTON_GPIO GPIO_NUM_10 +#define VOLUME_DOWN_BUTTON_GPIO GPIO_NUM_39 + +#define DISPLAY_SDA GPIO_NUM_41 +#define DISPLAY_SCL GPIO_NUM_42 +#define DISPLAY_RES GPIO_NUM_45 +#define DISPLAY_DC GPIO_NUM_40 +#define DISPLAY_CS GPIO_NUM_21 + +#define DISPLAY_WIDTH 240 +#define DISPLAY_HEIGHT 240 +#define DISPLAY_SWAP_XY false +#define DISPLAY_MIRROR_X false +#define DISPLAY_MIRROR_Y false +#define BACKLIGHT_INVERT false +#define DISPLAY_OFFSET_X 0 +#define DISPLAY_OFFSET_Y 0 + +#define DISPLAY_BACKLIGHT_PIN GPIO_NUM_20 +#define DISPLAY_BACKLIGHT_OUTPUT_INVERT false + + +#endif // _BOARD_CONFIG_H_ diff --git a/main/boards/zhengchen-1.54tft-wifi/config.json b/main/boards/zhengchen-1.54tft-wifi/config.json new file mode 100644 index 0000000..3c17d11 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/config.json @@ -0,0 +1,9 @@ +{ + "target": "esp32s3", + "builds": [ + { + "name": "zhengchen-1.54tft-wifi", + "sdkconfig_append": [] + } + ] +} \ No newline at end of file diff --git a/main/boards/zhengchen-1.54tft-wifi/power_manager.h b/main/boards/zhengchen-1.54tft-wifi/power_manager.h new file mode 100644 index 0000000..de6e82d --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/power_manager.h @@ -0,0 +1,238 @@ +#pragma once +#include +#include +#include +#include +#include +#include +#include +#include "application.h" +#include "zhengchen_lcd_display.h" + +class PowerManager { +private: + // 定时器句柄 + esp_timer_handle_t timer_handle_; + std::function on_charging_status_changed_; + std::function on_low_battery_status_changed_; + std::function on_temperature_changed_; + + gpio_num_t charging_pin_ = GPIO_NUM_NC; + std::vector adc_values_; + uint32_t battery_level_ = 0; + bool is_charging_ = false; + bool is_low_battery_ = false; + float current_temperature_ = 0.0f; + int ticks_ = 0; + const int kBatteryAdcInterval = 60; + const int kBatteryAdcDataCount = 3; + const int kLowBatteryLevel = 20; + const int kTemperatureReadInterval = 10; // 每 10 秒读取一次温度 + + adc_oneshot_unit_handle_t adc_handle_; + temperature_sensor_handle_t temp_sensor_ = NULL; + + void CheckBatteryStatus() { + // Get charging status + bool new_charging_status = gpio_get_level(charging_pin_) == 1; + if (new_charging_status != is_charging_) { + is_charging_ = new_charging_status; + if (on_charging_status_changed_) { + on_charging_status_changed_(is_charging_); + } + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据不足,则读取电池电量数据 + if (adc_values_.size() < kBatteryAdcDataCount) { + ReadBatteryAdcData(); + return; + } + + // 如果电池电量数据充足,则每 kBatteryAdcInterval 个 tick 读取一次电池电量数据 + ticks_++; + if (ticks_ % kBatteryAdcInterval == 0) { + ReadBatteryAdcData(); + } + + // 新增:周期性读取温度 + if (ticks_ % kTemperatureReadInterval == 0) { + ReadTemperature(); + } + } + + void ReadBatteryAdcData() { + // 读取 ADC 值 + int adc_value; + ESP_ERROR_CHECK(adc_oneshot_read(adc_handle_, ADC_CHANNEL_7, &adc_value)); + + + // 将 ADC 值添加到队列中 + adc_values_.push_back(adc_value); + if (adc_values_.size() > kBatteryAdcDataCount) { + adc_values_.erase(adc_values_.begin()); + } + uint32_t average_adc = 0; + for (auto value : adc_values_) { + average_adc += (value + 80); + } + average_adc /= adc_values_.size(); + + + // 定义电池电量区间 + const struct { + uint16_t adc; + uint8_t level; + } levels[] = { + {2030, 0}, + {2134, 20}, + {2252, 40}, + {2370, 60}, + {2488, 80}, + {2606, 100} + }; + // 低于最低值时 + if (average_adc < levels[0].adc) { + battery_level_ = 0; + } + // 高于最高值时 + else if (average_adc >= levels[5].adc) { + battery_level_ = 100; + } else { + // 线性插值计算中间值 + for (int i = 0; i < 5; i++) { + if (average_adc >= levels[i].adc && average_adc < levels[i+1].adc) { + float ratio = static_cast(average_adc - levels[i].adc) / (levels[i+1].adc - levels[i].adc); + battery_level_ = levels[i].level + ratio * (levels[i+1].level - levels[i].level); + break; + } + } + } + // 检查是否达到低电量阈值 + if (adc_values_.size() >= kBatteryAdcDataCount) { + bool new_low_battery_status = battery_level_ <= kLowBatteryLevel; + if (new_low_battery_status != is_low_battery_) { + is_low_battery_ = new_low_battery_status; + if (on_low_battery_status_changed_) { + on_low_battery_status_changed_(is_low_battery_); + } + } + } + + ESP_LOGI("PowerManager", "ADC value: %d average: %ld level: %ld", adc_value, average_adc, battery_level_); + } + + void ReadTemperature() { + float temperature = 0.0f; + ESP_ERROR_CHECK(temperature_sensor_get_celsius(temp_sensor_, &temperature)); + + if (abs(temperature - current_temperature_) >= 3.5f) { // 温度变化超过3.5°C才触发回调 + current_temperature_ = temperature; + if (on_temperature_changed_) { + on_temperature_changed_(current_temperature_); + } + ESP_LOGI("PowerManager", "Temperature updated: %.1f°C", current_temperature_); + } + } + + +public: + PowerManager(gpio_num_t pin) : charging_pin_(pin) { + + // 初始化充电引脚 + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = GPIO_MODE_INPUT; + io_conf.pin_bit_mask = (1ULL << charging_pin_); + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + gpio_config(&io_conf); + + // 创建电池电量检查定时器 + esp_timer_create_args_t timer_args = { + .callback = [](void* arg) { + PowerManager* self = static_cast(arg); + self->CheckBatteryStatus(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "battery_check_timer", + .skip_unhandled_events = true, + }; + ESP_ERROR_CHECK(esp_timer_create(&timer_args, &timer_handle_)); + ESP_ERROR_CHECK(esp_timer_start_periodic(timer_handle_, 1000000)); + + // 初始化 ADC + adc_oneshot_unit_init_cfg_t init_config = { + .unit_id = ADC_UNIT_1, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }; + ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc_handle_)); + + adc_oneshot_chan_cfg_t chan_config = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_12, + }; + ESP_ERROR_CHECK(adc_oneshot_config_channel(adc_handle_, ADC_CHANNEL_7, &chan_config)); + + // 初始化温度传感器 + temperature_sensor_config_t temp_config = { + .range_min = 10, + .range_max = 80, + .clk_src = TEMPERATURE_SENSOR_CLK_SRC_DEFAULT + }; + ESP_ERROR_CHECK(temperature_sensor_install(&temp_config, &temp_sensor_)); + ESP_ERROR_CHECK(temperature_sensor_enable(temp_sensor_)); + ESP_LOGI("PowerManager", "Temperature sensor initialized (new driver)"); + } + + ~PowerManager() { + if (timer_handle_) { + esp_timer_stop(timer_handle_); + esp_timer_delete(timer_handle_); + } + if (adc_handle_) { + adc_oneshot_del_unit(adc_handle_); + } + + if (temp_sensor_) { + temperature_sensor_disable(temp_sensor_); + temperature_sensor_uninstall(temp_sensor_); + } + + } + + bool IsCharging() { + // 如果电量已经满了,则不再显示充电中 + if (battery_level_ == 100) { + return false; + } + return is_charging_; + } + + bool IsDischarging() { + // 没有区分充电和放电,所以直接返回相反状态 + return !is_charging_; + } + + // 获取电池电量 + uint8_t GetBatteryLevel() { + // 返回电池电量 + return battery_level_; + } + + float GetTemperature() const { return current_temperature_; } // 获取当前温度 + + void OnTemperatureChanged(std::function callback) { + on_temperature_changed_ = callback; + } + + void OnLowBatteryStatusChanged(std::function callback) { + on_low_battery_status_changed_ = callback; + } + + void OnChargingStatusChanged(std::function callback) { + on_charging_status_changed_ = callback; + } +}; diff --git a/main/boards/zhengchen-1.54tft-wifi/zhengchen-1.54tft-wifi.cc b/main/boards/zhengchen-1.54tft-wifi/zhengchen-1.54tft-wifi.cc new file mode 100644 index 0000000..282a628 --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/zhengchen-1.54tft-wifi.cc @@ -0,0 +1,228 @@ +#include "wifi_board.h" +#include "codecs/no_audio_codec.h" +#include "zhengchen_lcd_display.h" +#include "system_reset.h" +#include "application.h" +#include "button.h" +#include "config.h" +#include "power_save_timer.h" +#include "led/single_led.h" +#include "assets/lang_config.h" +#include "power_manager.h" + +#include +#include +#include + +#include +#include + +#define TAG "ZHENGCHEN_1_54TFT_WIFI" + +class ZHENGCHEN_1_54TFT_WIFI : public WifiBoard { +private: + Button boot_button_; + Button volume_up_button_; + Button volume_down_button_; + ZHENGCHEN_LcdDisplay* display_; + PowerSaveTimer* power_save_timer_; + PowerManager* power_manager_; + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + void InitializePowerManager() { + power_manager_ = new PowerManager(GPIO_NUM_9); + power_manager_->OnTemperatureChanged([this](float chip_temp) { + display_->UpdateHighTempWarning(chip_temp); + }); + + power_manager_->OnChargingStatusChanged([this](bool is_charging) { + if (is_charging) { + power_save_timer_->SetEnabled(false); + ESP_LOGI("PowerManager", "Charging started"); + } else { + power_save_timer_->SetEnabled(true); + ESP_LOGI("PowerManager", "Charging stopped"); + } + }); + + } + + void InitializePowerSaveTimer() { + rtc_gpio_init(GPIO_NUM_2); + rtc_gpio_set_direction(GPIO_NUM_2, RTC_GPIO_MODE_OUTPUT_ONLY); + rtc_gpio_set_level(GPIO_NUM_2, 1); + + power_save_timer_ = new PowerSaveTimer(-1, 60, 300); + power_save_timer_->OnEnterSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(true); + GetBacklight()->SetBrightness(1); + }); + power_save_timer_->OnExitSleepMode([this]() { + GetDisplay()->SetPowerSaveMode(false); + GetBacklight()->RestoreBrightness(); + }); + power_save_timer_->SetEnabled(true); + } + + void InitializeSpi() { + spi_bus_config_t buscfg = {}; + buscfg.mosi_io_num = DISPLAY_SDA; + buscfg.miso_io_num = GPIO_NUM_NC; + buscfg.sclk_io_num = DISPLAY_SCL; + buscfg.quadwp_io_num = GPIO_NUM_NC; + buscfg.quadhd_io_num = GPIO_NUM_NC; + buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t); + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO)); + } + + void InitializeButtons() { + + boot_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) { + ResetWifiConfiguration(); + } + app.ToggleChatState(); + }); + + // 设置开机按钮的长按事件(直接进入配网模式) + boot_button_.OnLongPress([this]() { + // 唤醒电源保存定时器 + power_save_timer_->WakeUp(); + // 获取应用程序实例 + auto& app = Application::GetInstance(); + + // 进入配网模式 + app.SetDeviceState(kDeviceStateWifiConfiguring); + + // 重置WiFi配置以确保进入配网模式 + ResetWifiConfiguration(); + }); + + volume_up_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() + 10; + if (volume > 100) { + volume = 100; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume/10)); + }); + + volume_up_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(100); + GetDisplay()->ShowNotification(Lang::Strings::MAX_VOLUME); + }); + + volume_down_button_.OnClick([this]() { + power_save_timer_->WakeUp(); + auto codec = GetAudioCodec(); + auto volume = codec->output_volume() - 10; + if (volume < 0) { + volume = 0; + } + codec->SetOutputVolume(volume); + GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume/10)); + }); + + volume_down_button_.OnLongPress([this]() { + power_save_timer_->WakeUp(); + GetAudioCodec()->SetOutputVolume(0); + GetDisplay()->ShowNotification(Lang::Strings::MUTED); + }); + } + + void InitializeSt7789Display() { + ESP_LOGD(TAG, "Install panel IO"); + esp_lcd_panel_io_spi_config_t io_config = {}; + io_config.cs_gpio_num = DISPLAY_CS; + io_config.dc_gpio_num = DISPLAY_DC; + io_config.spi_mode = 3; + io_config.pclk_hz = 80 * 1000 * 1000; + io_config.trans_queue_depth = 10; + io_config.lcd_cmd_bits = 8; + io_config.lcd_param_bits = 8; + ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io_)); + + ESP_LOGD(TAG, "Install LCD driver"); + esp_lcd_panel_dev_config_t panel_config = {}; + panel_config.reset_gpio_num = DISPLAY_RES; + panel_config.rgb_ele_order = LCD_RGB_ELEMENT_ORDER_RGB; + panel_config.bits_per_pixel = 16; + ESP_ERROR_CHECK(esp_lcd_new_panel_st7789(panel_io_, &panel_config, &panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_init(panel_)); + ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel_, DISPLAY_SWAP_XY)); + ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel_, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y)); + ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel_, true)); + + display_ = new ZHENGCHEN_LcdDisplay(panel_io_, panel_, DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, + DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY); + display_->SetupHighTempWarningPopup(); + } + + void InitializeTools() { + } + +public: + ZHENGCHEN_1_54TFT_WIFI() : + boot_button_(BOOT_BUTTON_GPIO), + volume_up_button_(VOLUME_UP_BUTTON_GPIO), + volume_down_button_(VOLUME_DOWN_BUTTON_GPIO) { + InitializePowerManager(); + InitializePowerSaveTimer(); + InitializeSpi(); + InitializeButtons(); + InitializeSt7789Display(); + InitializeTools(); + GetBacklight()->RestoreBrightness(); + } + + // 获取音频编解码器 + virtual AudioCodec* GetAudioCodec() override { + // 静态实例化NoAudioCodecSimplex类 + static NoAudioCodecSimplex audio_codec(AUDIO_INPUT_SAMPLE_RATE, AUDIO_OUTPUT_SAMPLE_RATE, + AUDIO_I2S_SPK_GPIO_BCLK, AUDIO_I2S_SPK_GPIO_LRCK, AUDIO_I2S_SPK_GPIO_DOUT, AUDIO_I2S_MIC_GPIO_SCK, AUDIO_I2S_MIC_GPIO_WS, AUDIO_I2S_MIC_GPIO_DIN); + // 返回音频编解码器 + return &audio_codec; + } + + virtual Display* GetDisplay() override { + return display_; + } + + virtual Backlight* GetBacklight() override { + static PwmBacklight backlight(DISPLAY_BACKLIGHT_PIN, DISPLAY_BACKLIGHT_OUTPUT_INVERT); + return &backlight; + } + + virtual bool GetBatteryLevel(int& level, bool& charging, bool& discharging) override { + static bool last_discharging = false; + charging = power_manager_->IsCharging(); + discharging = power_manager_->IsDischarging(); + if (discharging != last_discharging) { + power_save_timer_->SetEnabled(discharging); + last_discharging = discharging; + } + level = std::max(power_manager_->GetBatteryLevel(), 20); + return true; + } + + virtual bool GetTemperature(float& esp32temp) override { + esp32temp = power_manager_->GetTemperature(); + return true; + } + + virtual void SetPowerSaveMode(bool enabled) override { + if (!enabled) { + power_save_timer_->WakeUp(); + } + WifiBoard::SetPowerSaveMode(enabled); + } +}; + +DECLARE_BOARD(ZHENGCHEN_1_54TFT_WIFI); diff --git a/main/boards/zhengchen-1.54tft-wifi/zhengchen_lcd_display.h b/main/boards/zhengchen-1.54tft-wifi/zhengchen_lcd_display.h new file mode 100644 index 0000000..fa6222a --- /dev/null +++ b/main/boards/zhengchen-1.54tft-wifi/zhengchen_lcd_display.h @@ -0,0 +1,66 @@ +#ifndef ZHENGCHEN_LCD_DISPLAY_H +#define ZHENGCHEN_LCD_DISPLAY_H + +#include "display/lcd_display.h" +#include "lvgl_theme.h" +#include + +class ZHENGCHEN_LcdDisplay : public SpiLcdDisplay { +protected: + lv_obj_t* high_temp_popup_ = nullptr; // 高温警告弹窗 + lv_obj_t* high_temp_label_ = nullptr; // 高温警告标签 + +public: + // 继承构造函数 + using SpiLcdDisplay::SpiLcdDisplay; + + void SetupHighTempWarningPopup() { + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + // 创建高温警告弹窗 + high_temp_popup_ = lv_obj_create(lv_screen_active()); // 使用当前屏幕 + lv_obj_set_scrollbar_mode(high_temp_popup_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_size(high_temp_popup_, LV_HOR_RES * 0.9, text_font->line_height * 2); + lv_obj_align(high_temp_popup_, LV_ALIGN_BOTTOM_MID, 0, 0); + lv_obj_set_style_bg_color(high_temp_popup_, lv_palette_main(LV_PALETTE_RED), 0); + lv_obj_set_style_radius(high_temp_popup_, 10, 0); + + // 创建警告标签 + high_temp_label_ = lv_label_create(high_temp_popup_); + lv_label_set_text(high_temp_label_, "警告:温度过高"); + lv_obj_set_style_text_color(high_temp_label_, lv_color_white(), 0); + lv_obj_center(high_temp_label_); + + // 默认隐藏 + lv_obj_add_flag(high_temp_popup_, LV_OBJ_FLAG_HIDDEN); + } + + void UpdateHighTempWarning(float chip_temp, float threshold = 75.0f) { + if (high_temp_popup_ == nullptr) { + ESP_LOGW("ZHENGCHEN_LcdDisplay", "High temp popup not initialized!"); + return; + } + + if (chip_temp >= threshold) { + ShowHighTempWarning(); + } else { + HideHighTempWarning(); + } + } + + void ShowHighTempWarning() { + if (high_temp_popup_ && lv_obj_has_flag(high_temp_popup_, LV_OBJ_FLAG_HIDDEN)) { + lv_obj_remove_flag(high_temp_popup_, LV_OBJ_FLAG_HIDDEN); + } + } + + void HideHighTempWarning() { + if (high_temp_popup_ && !lv_obj_has_flag(high_temp_popup_, LV_OBJ_FLAG_HIDDEN)) { + lv_obj_add_flag(high_temp_popup_, LV_OBJ_FLAG_HIDDEN); + } + } +}; + + + +#endif // ZHENGCHEN_LCD_DISPLAY_H \ No newline at end of file diff --git a/main/device_state.h b/main/device_state.h new file mode 100644 index 0000000..4ffafae --- /dev/null +++ b/main/device_state.h @@ -0,0 +1,18 @@ +#ifndef _DEVICE_STATE_H_ +#define _DEVICE_STATE_H_ + +enum DeviceState { + kDeviceStateUnknown, + kDeviceStateStarting, + kDeviceStateWifiConfiguring, + kDeviceStateIdle, + kDeviceStateConnecting, + kDeviceStateListening, + kDeviceStateSpeaking, + kDeviceStateUpgrading, + kDeviceStateActivating, + kDeviceStateAudioTesting, + kDeviceStateFatalError +}; + +#endif // _DEVICE_STATE_H_ \ No newline at end of file diff --git a/main/device_state_event.cc b/main/device_state_event.cc new file mode 100644 index 0000000..81e2be2 --- /dev/null +++ b/main/device_state_event.cc @@ -0,0 +1,46 @@ +#include "device_state_event.h" + +ESP_EVENT_DEFINE_BASE(XIAOZHI_STATE_EVENTS); + +DeviceStateEventManager& DeviceStateEventManager::GetInstance() { + static DeviceStateEventManager instance; + return instance; +} + +void DeviceStateEventManager::RegisterStateChangeCallback(std::function callback) { + std::lock_guard lock(mutex_); + callbacks_.push_back(callback); +} + +void DeviceStateEventManager::PostStateChangeEvent(DeviceState previous_state, DeviceState current_state) { + device_state_event_data_t event_data = { + .previous_state = previous_state, + .current_state = current_state + }; + esp_event_post(XIAOZHI_STATE_EVENTS, XIAOZHI_STATE_CHANGED_EVENT, &event_data, sizeof(event_data), portMAX_DELAY); +} + +std::vector> DeviceStateEventManager::GetCallbacks() { + std::lock_guard lock(mutex_); + return callbacks_; +} + +DeviceStateEventManager::DeviceStateEventManager() { + esp_err_t err = esp_event_loop_create_default(); + if (err != ESP_OK && err != ESP_ERR_INVALID_STATE) { + ESP_ERROR_CHECK(err); + } + + ESP_ERROR_CHECK(esp_event_handler_register(XIAOZHI_STATE_EVENTS, XIAOZHI_STATE_CHANGED_EVENT, + [](void* handler_args, esp_event_base_t base, int32_t id, void* event_data) { + auto* data = static_cast(event_data); + auto& manager = DeviceStateEventManager::GetInstance(); + for (const auto& callback : manager.GetCallbacks()) { + callback(data->previous_state, data->current_state); + } + }, nullptr)); +} + +DeviceStateEventManager::~DeviceStateEventManager() { + esp_event_handler_unregister(XIAOZHI_STATE_EVENTS, XIAOZHI_STATE_CHANGED_EVENT, nullptr); +} \ No newline at end of file diff --git a/main/device_state_event.h b/main/device_state_event.h new file mode 100644 index 0000000..03e2713 --- /dev/null +++ b/main/device_state_event.h @@ -0,0 +1,39 @@ +#ifndef _DEVICE_STATE_EVENT_H_ +#define _DEVICE_STATE_EVENT_H_ + +#include +#include +#include +#include +#include "device_state.h" + +ESP_EVENT_DECLARE_BASE(XIAOZHI_STATE_EVENTS); + +enum { + XIAOZHI_STATE_CHANGED_EVENT, +}; + +struct device_state_event_data_t { + DeviceState previous_state; + DeviceState current_state; +}; + +class DeviceStateEventManager { +public: + static DeviceStateEventManager& GetInstance(); + DeviceStateEventManager(const DeviceStateEventManager&) = delete; + DeviceStateEventManager& operator=(const DeviceStateEventManager&) = delete; + + void RegisterStateChangeCallback(std::function callback); + void PostStateChangeEvent(DeviceState previous_state, DeviceState current_state); + std::vector> GetCallbacks(); + +private: + DeviceStateEventManager(); + ~DeviceStateEventManager(); + + std::vector> callbacks_; + std::mutex mutex_; +}; + +#endif // _DEVICE_STATE_EVENT_H_ \ No newline at end of file diff --git a/main/display/display.cc b/main/display/display.cc new file mode 100644 index 0000000..b874533 --- /dev/null +++ b/main/display/display.cc @@ -0,0 +1,58 @@ +#include +#include +#include +#include +#include +#include + +#include "display.h" +#include "board.h" +#include "application.h" +#include "audio_codec.h" +#include "settings.h" +#include "assets/lang_config.h" +#include "uart_component.h" + +#define TAG "Display" + +Display::Display() { +} + +Display::~Display() { +} + +void Display::SetStatus(const char* status) { + ESP_LOGW(TAG, "SetStatus: %s", status); +} + +void Display::ShowNotification(const std::string ¬ification, int duration_ms) { + ShowNotification(notification.c_str(), duration_ms); +} + +void Display::ShowNotification(const char* notification, int duration_ms) { + ESP_LOGW(TAG, "ShowNotification: %s", notification); +} + +void Display::UpdateStatusBar(bool update_all) { +} + + +void Display::SetEmotion(const char* emotion) { + ESP_LOGW(TAG, "SetEmotion: %s", emotion); + uart_send_string(emotion); +} + +void Display::SetChatMessage(const char* role, const char* content) { + ESP_LOGW(TAG, "Role:%s", role); + ESP_LOGW(TAG, " %s", content); +} + +void Display::SetTheme(Theme* theme) { + current_theme_ = theme; + Settings settings("display", true); + settings.SetString("theme", theme->name()); +} + +void Display::SetPowerSaveMode(bool on) { + ESP_LOGW(TAG, "SetPowerSaveMode: %d", on); +} diff --git a/main/display/display.h b/main/display/display.h new file mode 100644 index 0000000..b24da4e --- /dev/null +++ b/main/display/display.h @@ -0,0 +1,81 @@ +#ifndef DISPLAY_H +#define DISPLAY_H + +#include "emoji_collection.h" + +#ifndef CONFIG_USE_EMOTE_MESSAGE_STYLE +#define HAVE_LVGL 1 +#include +#endif + +#include +#include +#include + +#include +#include + +class Theme { +public: + Theme(const std::string& name) : name_(name) {} + virtual ~Theme() = default; + + inline std::string name() const { return name_; } +private: + std::string name_; +}; + +class Display { +public: + Display(); + virtual ~Display(); + + virtual void SetStatus(const char* status); + virtual void ShowNotification(const char* notification, int duration_ms = 3000); + virtual void ShowNotification(const std::string ¬ification, int duration_ms = 3000); + virtual void SetEmotion(const char* emotion); + virtual void SetChatMessage(const char* role, const char* content); + virtual void SetTheme(Theme* theme); + virtual Theme* GetTheme() { return current_theme_; } + virtual void UpdateStatusBar(bool update_all = false); + virtual void SetPowerSaveMode(bool on); + + inline int width() const { return width_; } + inline int height() const { return height_; } + +protected: + int width_ = 0; + int height_ = 0; + + Theme* current_theme_ = nullptr; + + friend class DisplayLockGuard; + virtual bool Lock(int timeout_ms = 0) = 0; + virtual void Unlock() = 0; +}; + + +class DisplayLockGuard { +public: + DisplayLockGuard(Display *display) : display_(display) { + if (!display_->Lock(30000)) { + ESP_LOGE("Display", "Failed to lock display"); + } + } + ~DisplayLockGuard() { + display_->Unlock(); + } + +private: + Display *display_; +}; + +class NoDisplay : public Display { +private: + virtual bool Lock(int timeout_ms = 0) override { + return true; + } + virtual void Unlock() override {} +}; + +#endif diff --git a/main/display/emote_display.cc b/main/display/emote_display.cc new file mode 100644 index 0000000..5c6dec3 --- /dev/null +++ b/main/display/emote_display.cc @@ -0,0 +1,655 @@ +#include "emote_display.h" + +// Standard C++ headers +#include +#include +#include +#include + +// Standard C headers +#include +#include + +// ESP-IDF headers +#include +#include +#include + +// FreeRTOS headers +#include +#include + +// Project headers +#include "assets.h" +#include "assets/lang_config.h" +#include "board.h" +#include "gfx.h" + +LV_FONT_DECLARE(BUILTIN_TEXT_FONT); + +namespace emote { + +// ============================================================================ +// Constants and Type Definitions +// ============================================================================ + +static const char* TAG = "EmoteDisplay"; + +// UI Element Names - Centralized Management +#define UI_ELEMENT_EYE_ANIM "eye_anim" +#define UI_ELEMENT_TOAST_LABEL "toast_label" +#define UI_ELEMENT_CLOCK_LABEL "clock_label" +#define UI_ELEMENT_LISTEN_ANIM "listen_anim" +#define UI_ELEMENT_STATUS_ICON "status_icon" + +// Icon Names - Centralized Management +#define ICON_MIC "icon_mic" +#define ICON_BATTERY "icon_Battery" +#define ICON_SPEAKER_ZZZ "icon_speaker_zzz" +#define ICON_WIFI_FAILED "icon_WiFi_failed" +#define ICON_WIFI_OK "icon_wifi" +#define ICON_LISTEN "listen" + +using FlushIoReadyCallback = std::function; +using FlushCallback = std::function; + +// ============================================================================ +// Global Variables +// ============================================================================ + +// UI element management +static gfx_obj_t* g_obj_label_toast = nullptr; +static gfx_obj_t* g_obj_label_clock = nullptr; +static gfx_obj_t* g_obj_anim_eye = nullptr; +static gfx_obj_t* g_obj_anim_listen = nullptr; +static gfx_obj_t* g_obj_img_status = nullptr; + +// Track current icon to determine when to show time +static std::string g_current_icon_type = ICON_WIFI_FAILED; +static gfx_image_dsc_t g_icon_img_dsc; + + +// ============================================================================ +// Forward Declarations +// ============================================================================ + +class EmoteDisplay; +class EmoteEngine; + +enum class UIDisplayMode : uint8_t { + SHOW_LISTENING = 1, // Show g_obj_anim_listen + SHOW_TIME = 2, // Show g_obj_label_clock + SHOW_TIPS = 3 // Show g_obj_label_toast +}; + +// ============================================================================ +// Helper Functions +// ============================================================================ + +// Function to convert align string to GFX_ALIGN enum value +char StringToGfxAlign(const std::string &align_str) +{ + static const std::unordered_map align_map = { + {"GFX_ALIGN_DEFAULT", GFX_ALIGN_DEFAULT}, + {"GFX_ALIGN_TOP_LEFT", GFX_ALIGN_TOP_LEFT}, + {"GFX_ALIGN_TOP_MID", GFX_ALIGN_TOP_MID}, + {"GFX_ALIGN_TOP_RIGHT", GFX_ALIGN_TOP_RIGHT}, + {"GFX_ALIGN_LEFT_MID", GFX_ALIGN_LEFT_MID}, + {"GFX_ALIGN_CENTER", GFX_ALIGN_CENTER}, + {"GFX_ALIGN_RIGHT_MID", GFX_ALIGN_RIGHT_MID}, + {"GFX_ALIGN_BOTTOM_LEFT", GFX_ALIGN_BOTTOM_LEFT}, + {"GFX_ALIGN_BOTTOM_MID", GFX_ALIGN_BOTTOM_MID}, + {"GFX_ALIGN_BOTTOM_RIGHT", GFX_ALIGN_BOTTOM_RIGHT}, + {"GFX_ALIGN_OUT_TOP_LEFT", GFX_ALIGN_OUT_TOP_LEFT}, + {"GFX_ALIGN_OUT_TOP_MID", GFX_ALIGN_OUT_TOP_MID}, + {"GFX_ALIGN_OUT_TOP_RIGHT", GFX_ALIGN_OUT_TOP_RIGHT}, + {"GFX_ALIGN_OUT_LEFT_TOP", GFX_ALIGN_OUT_LEFT_TOP}, + {"GFX_ALIGN_OUT_LEFT_MID", GFX_ALIGN_OUT_LEFT_MID}, + {"GFX_ALIGN_OUT_LEFT_BOTTOM", GFX_ALIGN_OUT_LEFT_BOTTOM}, + {"GFX_ALIGN_OUT_RIGHT_TOP", GFX_ALIGN_OUT_RIGHT_TOP}, + {"GFX_ALIGN_OUT_RIGHT_MID", GFX_ALIGN_OUT_RIGHT_MID}, + {"GFX_ALIGN_OUT_RIGHT_BOTTOM", GFX_ALIGN_OUT_RIGHT_BOTTOM}, + {"GFX_ALIGN_OUT_BOTTOM_LEFT", GFX_ALIGN_OUT_BOTTOM_LEFT}, + {"GFX_ALIGN_OUT_BOTTOM_MID", GFX_ALIGN_OUT_BOTTOM_MID}, + {"GFX_ALIGN_OUT_BOTTOM_RIGHT", GFX_ALIGN_OUT_BOTTOM_RIGHT} + }; + + const auto it = align_map.find(align_str); + if (it != align_map.cend()) { + return it->second; + } + + ESP_LOGW(TAG, "Unknown align string: %s, using GFX_ALIGN_DEFAULT", align_str.c_str()); + return GFX_ALIGN_DEFAULT; +} + +// ============================================================================ +// EmoteEngine Class Declaration +// ============================================================================ + +class EmoteEngine { +public: + EmoteEngine(const esp_lcd_panel_handle_t panel, const esp_lcd_panel_io_handle_t panel_io, + const int width, const int height, EmoteDisplay* const display); + ~EmoteEngine(); + + void SetEyes(const std::string &emoji_name, const bool repeat, const int fps, EmoteDisplay* const display); + void SetIcon(const std::string &icon_name, EmoteDisplay* const display); + + void* GetEngineHandle() const + { + return engine_handle_; + } + + // Callback functions (public to be accessible from static helper functions) + static bool OnFlushIoReady(const esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_io_event_data_t* const edata, void* const user_ctx); + static void OnFlush(const gfx_handle_t handle, const int x_start, const int y_start, const int x_end, const int y_end, const void* const color_data); + +private: + gfx_handle_t engine_handle_; +}; + +// ============================================================================ +// UI Management Functions +// ============================================================================ + +static void SetUIDisplayMode(const UIDisplayMode mode, EmoteDisplay* const display) +{ + if (!display) { + ESP_LOGE(TAG, "SetUIDisplayMode: display is nullptr"); + return; + } + + gfx_obj_set_visible(g_obj_anim_listen, false); + gfx_obj_set_visible(g_obj_label_clock, false); + gfx_obj_set_visible(g_obj_label_toast, false); + + // Show the selected control + switch (mode) { + case UIDisplayMode::SHOW_LISTENING: { + gfx_obj_set_visible(g_obj_anim_listen, true); + const AssetData emoji_data = display->GetIconData(ICON_LISTEN); + if (emoji_data.data) { + gfx_anim_set_src(g_obj_anim_listen, emoji_data.data, emoji_data.size); + gfx_anim_set_segment(g_obj_anim_listen, 0, 0xFFFF, 20, true); + gfx_anim_start(g_obj_anim_listen); + } + break; + } + case UIDisplayMode::SHOW_TIME: + gfx_obj_set_visible(g_obj_label_clock, true); + break; + case UIDisplayMode::SHOW_TIPS: + gfx_obj_set_visible(g_obj_label_toast, true); + break; + } +} + +// ============================================================================ +// Graphics Initialization Functions +// ============================================================================ + +static void InitializeGraphics(const esp_lcd_panel_handle_t panel, gfx_handle_t* const engine_handle, + const int width, const int height) +{ + if (!panel || !engine_handle) { + ESP_LOGE(TAG, "InitializeGraphics: Invalid parameters"); + return; + } + + gfx_core_config_t gfx_cfg = { + .flush_cb = EmoteEngine::OnFlush, + .user_data = panel, + .flags = { + .swap = true, + .double_buffer = true, + .buff_dma = true, + }, + .h_res = static_cast(width), + .v_res = static_cast(height), + .fps = 30, + .buffers = { + .buf1 = nullptr, + .buf2 = nullptr, + .buf_pixels = static_cast(width * 16), + }, + .task = GFX_EMOTE_INIT_CONFIG() + }; + + gfx_cfg.task.task_stack_caps = MALLOC_CAP_DEFAULT; + gfx_cfg.task.task_affinity = 0; + gfx_cfg.task.task_priority = 5; + gfx_cfg.task.task_stack = 8 * 1024; + + *engine_handle = gfx_emote_init(&gfx_cfg); +} + +static void SetupUI(const gfx_handle_t engine_handle, EmoteDisplay* const display) +{ + if (!display) { + ESP_LOGE(TAG, "SetupUI: display is nullptr"); + return; + } + + gfx_emote_set_bg_color(engine_handle, GFX_COLOR_HEX(0x000000)); + + g_obj_anim_eye = gfx_anim_create(engine_handle); + gfx_obj_align(g_obj_anim_eye, GFX_ALIGN_LEFT_MID, 10, 30); + gfx_anim_set_auto_mirror(g_obj_anim_eye, true); + gfx_obj_set_visible(g_obj_anim_eye, false); + + g_obj_label_toast = gfx_label_create(engine_handle); + gfx_obj_align(g_obj_label_toast, GFX_ALIGN_TOP_MID, 0, 20); + gfx_obj_set_size(g_obj_label_toast, 200, 40); + gfx_label_set_text(g_obj_label_toast, Lang::Strings::INITIALIZING); + gfx_label_set_color(g_obj_label_toast, GFX_COLOR_HEX(0xFFFFFF)); + gfx_label_set_text_align(g_obj_label_toast, GFX_TEXT_ALIGN_CENTER); + gfx_label_set_long_mode(g_obj_label_toast, GFX_LABEL_LONG_SCROLL); + gfx_label_set_scroll_speed(g_obj_label_toast, 20); + gfx_label_set_scroll_loop(g_obj_label_toast, true); + gfx_label_set_font(g_obj_label_toast, (gfx_font_t)&BUILTIN_TEXT_FONT); + + g_obj_label_clock = gfx_label_create(engine_handle); + gfx_obj_align(g_obj_label_clock, GFX_ALIGN_TOP_MID, 0, 15); + gfx_obj_set_size(g_obj_label_clock, 200, 50); + gfx_label_set_text(g_obj_label_clock, "--:--"); + gfx_label_set_color(g_obj_label_clock, GFX_COLOR_HEX(0xFFFFFF)); + gfx_label_set_text_align(g_obj_label_clock, GFX_TEXT_ALIGN_CENTER); + gfx_label_set_font(g_obj_label_clock, (gfx_font_t)&BUILTIN_TEXT_FONT); + + g_obj_anim_listen = gfx_anim_create(engine_handle); + gfx_obj_align(g_obj_anim_listen, GFX_ALIGN_TOP_MID, 0, 5); + gfx_anim_start(g_obj_anim_listen); + gfx_obj_set_visible(g_obj_anim_listen, false); + + g_obj_img_status = gfx_img_create(engine_handle); + gfx_obj_align(g_obj_img_status, GFX_ALIGN_TOP_MID, -120, 18); + + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, display); +} + +static void RegisterCallbacks(const esp_lcd_panel_io_handle_t panel_io, const gfx_handle_t engine_handle) +{ + if (!panel_io) { + ESP_LOGE(TAG, "RegisterCallbacks: panel_io is nullptr"); + return; + } + + const esp_lcd_panel_io_callbacks_t cbs = { + .on_color_trans_done = EmoteEngine::OnFlushIoReady, + }; + esp_lcd_panel_io_register_event_callbacks(panel_io, &cbs, engine_handle); +} + +// ============================================================================ +// EmoteEngine Class Implementation +// ============================================================================ + +EmoteEngine::EmoteEngine(const esp_lcd_panel_handle_t panel, const esp_lcd_panel_io_handle_t panel_io, + const int width, const int height, EmoteDisplay* const display) +{ + InitializeGraphics(panel, &engine_handle_, width, height); + + if (display) { + gfx_emote_lock(engine_handle_); + SetupUI(engine_handle_, display); + gfx_emote_unlock(engine_handle_); + } + + RegisterCallbacks(panel_io, engine_handle_); +} + +EmoteEngine::~EmoteEngine() +{ + if (engine_handle_) { + gfx_emote_deinit(engine_handle_); + engine_handle_ = nullptr; + } +} + +void EmoteEngine::SetEyes(const std::string &emoji_name, const bool repeat, const int fps, EmoteDisplay* const display) +{ + if (!engine_handle_) { + ESP_LOGE(TAG, "SetEyes: engine_handle_ is nullptr"); + return; + } + + if (!display) { + ESP_LOGE(TAG, "SetEyes: display is nullptr"); + return; + } + + const AssetData emoji_data = display->GetEmojiData(emoji_name); + if (emoji_data.data) { + DisplayLockGuard lock(display); + gfx_anim_set_src(g_obj_anim_eye, emoji_data.data, emoji_data.size); + gfx_anim_set_segment(g_obj_anim_eye, 0, 0xFFFF, fps, repeat); + gfx_obj_set_visible(g_obj_anim_eye, true); + gfx_anim_start(g_obj_anim_eye); + } else { + ESP_LOGW(TAG, "SetEyes: No emoji data found for %s", emoji_name.c_str()); + } +} + +void EmoteEngine::SetIcon(const std::string &icon_name, EmoteDisplay* const display) +{ + if (!engine_handle_) { + ESP_LOGE(TAG, "SetIcon: engine_handle_ is nullptr"); + return; + } + + if (!display) { + ESP_LOGE(TAG, "SetIcon: display is nullptr"); + return; + } + + const AssetData icon_data = display->GetIconData(icon_name); + if (icon_data.data) { + DisplayLockGuard lock(display); + + std::memcpy(&g_icon_img_dsc.header, icon_data.data, sizeof(gfx_image_header_t)); + g_icon_img_dsc.data = static_cast(icon_data.data) + sizeof(gfx_image_header_t); + g_icon_img_dsc.data_size = icon_data.size - sizeof(gfx_image_header_t); + + gfx_img_set_src(g_obj_img_status, &g_icon_img_dsc); + } else { + ESP_LOGW(TAG, "SetIcon: No icon data found for %s", icon_name.c_str()); + } + g_current_icon_type = icon_name; +} + +bool EmoteEngine::OnFlushIoReady(const esp_lcd_panel_io_handle_t panel_io, + esp_lcd_panel_io_event_data_t* const edata, + void* const user_ctx) +{ + return true; +} + +void EmoteEngine::OnFlush(const gfx_handle_t handle, const int x_start, const int y_start, + const int x_end, const int y_end, const void* const color_data) +{ + auto* const panel = static_cast(gfx_emote_get_user_data(handle)); + if (panel) { + esp_lcd_panel_draw_bitmap(panel, x_start, y_start, x_end, y_end, color_data); + } + gfx_emote_flush_ready(handle, true); +} + +// ============================================================================ +// EmoteDisplay Class Implementation +// ============================================================================ + +EmoteDisplay::EmoteDisplay(const esp_lcd_panel_handle_t panel, const esp_lcd_panel_io_handle_t panel_io, + const int width, const int height) +{ + InitializeEngine(panel, panel_io, width, height); +} + +EmoteDisplay::~EmoteDisplay() = default; + +void EmoteDisplay::SetEmotion(const char* const emotion) +{ + if (!emotion) { + ESP_LOGE(TAG, "SetEmotion: emotion is nullptr"); + return; + } + + ESP_LOGI(TAG, "SetEmotion: %s", emotion); + if (!engine_) { + return; + } + + const AssetData emoji_data = GetEmojiData(emotion); + bool repeat = emoji_data.loop; + int fps = emoji_data.fps > 0 ? emoji_data.fps : 20; + + if (std::strcmp(emotion, "idle") == 0 || std::strcmp(emotion, "neutral") == 0) { + repeat = false; + } + + DisplayLockGuard lock(this); + engine_->SetEyes(emotion, repeat, fps, this); +} + +void EmoteDisplay::SetChatMessage(const char* const role, const char* const content) +{ + if (!engine_) { + return; + } + + DisplayLockGuard lock(this); + if (content && strlen(content) > 0) { + gfx_label_set_text(g_obj_label_toast, content); + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, this); + } +} + +void EmoteDisplay::SetStatus(const char* const status) +{ + if (!status) { + ESP_LOGE(TAG, "SetStatus: status is nullptr"); + return; + } + + if (!engine_) { + return; + } + + DisplayLockGuard lock(this); + + if (std::strcmp(status, Lang::Strings::LISTENING) == 0) { + SetUIDisplayMode(UIDisplayMode::SHOW_LISTENING, this); + engine_->SetEyes("happy", true, 20, this); + engine_->SetIcon(ICON_MIC, this); + } else if (std::strcmp(status, Lang::Strings::STANDBY) == 0) { + SetUIDisplayMode(UIDisplayMode::SHOW_TIME, this); + engine_->SetIcon(ICON_BATTERY, this); + } else if (std::strcmp(status, Lang::Strings::SPEAKING) == 0) { + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, this); + engine_->SetIcon(ICON_SPEAKER_ZZZ, this); + } else if (std::strcmp(status, Lang::Strings::ERROR) == 0) { + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, this); + engine_->SetIcon(ICON_WIFI_FAILED, this); + } + + if (std::strcmp(status, Lang::Strings::CONNECTING) != 0) { + gfx_label_set_text(g_obj_label_toast, status); + } +} + +void EmoteDisplay::ShowNotification(const char* notification, int duration_ms) +{ + if (!notification || !engine_) { + return; + } + ESP_LOGI(TAG, "ShowNotification: %s", notification); + + DisplayLockGuard lock(this); + gfx_label_set_text(g_obj_label_toast, notification); + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, this); +} + +void EmoteDisplay::UpdateStatusBar(bool update_all) +{ + if (!engine_) { + return; + } + + // Only display time when battery icon is shown + DisplayLockGuard lock(this); + if (g_current_icon_type == ICON_BATTERY) { + time_t now; + struct tm timeinfo; + time(&now); + + setenv("TZ", "GMT+0", 1); + tzset(); + localtime_r(&now, &timeinfo); + + char time_str[6]; + snprintf(time_str, sizeof(time_str), "%02d:%02d", timeinfo.tm_hour, timeinfo.tm_min); + + DisplayLockGuard lock(this); + gfx_label_set_text(g_obj_label_clock, time_str); + SetUIDisplayMode(UIDisplayMode::SHOW_TIME, this); + } +} + +void EmoteDisplay::SetPowerSaveMode(bool on) +{ + if (!engine_) { + return; + } + + DisplayLockGuard lock(this); + ESP_LOGI(TAG, "SetPowerSaveMode: %s", on ? "ON" : "OFF"); + if (on) { + gfx_anim_stop(g_obj_anim_eye); + } else { + gfx_anim_start(g_obj_anim_eye); + } +} + +void EmoteDisplay::SetPreviewImage(const void* image) +{ + if (image) { + ESP_LOGI(TAG, "SetPreviewImage: Preview image not supported, using default icon"); + if (engine_) { + } + } +} + +void EmoteDisplay::SetTheme(Theme* const theme) +{ + ESP_LOGI(TAG, "SetTheme: %p", theme); + +} +void EmoteDisplay::AddEmojiData(const std::string &name, const void* const data, const size_t size, + uint8_t fps, bool loop, bool lack) +{ + emoji_data_map_[name] = AssetData(data, size, fps, loop, lack); + ESP_LOGD(TAG, "Added emoji data: %s, size: %d, fps: %d, loop: %s, lack: %s", + name.c_str(), size, fps, loop ? "true" : "false", lack ? "true" : "false"); + + DisplayLockGuard lock(this); + if (name == "happy") { + engine_->SetEyes("happy", loop, fps > 0 ? fps : 20, this); + } +} + +void EmoteDisplay::AddIconData(const std::string &name, const void* const data, const size_t size) +{ + icon_data_map_[name] = AssetData(data, size); + ESP_LOGD(TAG, "Added icon data: %s, size: %d", name.c_str(), size); + + DisplayLockGuard lock(this); + if (name == ICON_WIFI_FAILED) { + SetUIDisplayMode(UIDisplayMode::SHOW_TIPS, this); + engine_->SetIcon(ICON_WIFI_FAILED, this); + } +} + +void EmoteDisplay::AddLayoutData(const std::string &name, const std::string &align_str, + const int x, const int y, const int width, const int height) +{ + const char align_enum = StringToGfxAlign(align_str); + ESP_LOGI(TAG, "layout: %-12s | %-20s(%d) | %4d, %4d | %4dx%-4d", + name.c_str(), align_str.c_str(), align_enum, x, y, width, height); + + struct UIElement { + gfx_obj_t* obj; + const char* name; + }; + + const UIElement elements[] = { + {g_obj_anim_eye, UI_ELEMENT_EYE_ANIM}, + {g_obj_label_toast, UI_ELEMENT_TOAST_LABEL}, + {g_obj_label_clock, UI_ELEMENT_CLOCK_LABEL}, + {g_obj_anim_listen, UI_ELEMENT_LISTEN_ANIM}, + {g_obj_img_status, UI_ELEMENT_STATUS_ICON} + }; + + DisplayLockGuard lock(this); + for (const auto &element : elements) { + if (name == element.name && element.obj) { + gfx_obj_align(element.obj, align_enum, x, y); + if (width > 0 && height > 0) { + gfx_obj_set_size(element.obj, width, height); + } + return; + } + } + + ESP_LOGW(TAG, "AddLayoutData: UI element '%s' not found", name.c_str()); +} + +void EmoteDisplay::AddTextFont(std::shared_ptr text_font) +{ + if (!text_font) { + ESP_LOGW(TAG, "AddTextFont: text_font is nullptr"); + return; + } + + text_font_ = text_font; + ESP_LOGD(TAG, "AddTextFont: Text font added successfully"); + + DisplayLockGuard lock(this); + if (g_obj_label_toast && text_font_) { + gfx_label_set_font(g_obj_label_toast, const_cast(static_cast(text_font_->font()))); + } + if (g_obj_label_clock && text_font_) { + gfx_label_set_font(g_obj_label_clock, const_cast(static_cast(text_font_->font()))); + } +} + +AssetData EmoteDisplay::GetEmojiData(const std::string &name) const +{ + const auto it = emoji_data_map_.find(name); + if (it != emoji_data_map_.cend()) { + return it->second; + } + return AssetData(); +} + +AssetData EmoteDisplay::GetIconData(const std::string &name) const +{ + const auto it = icon_data_map_.find(name); + if (it != icon_data_map_.cend()) { + return it->second; + } + return AssetData(); +} + +EmoteEngine* EmoteDisplay::GetEngine() const +{ + return engine_.get(); +} + +void* EmoteDisplay::GetEngineHandle() const +{ + return engine_ ? engine_->GetEngineHandle() : nullptr; +} + +void EmoteDisplay::InitializeEngine(const esp_lcd_panel_handle_t panel, const esp_lcd_panel_io_handle_t panel_io, + const int width, const int height) +{ + engine_ = std::make_unique(panel, panel_io, width, height, this); +} + +bool EmoteDisplay::Lock(const int timeout_ms) +{ + if (engine_ && engine_->GetEngineHandle()) { + gfx_emote_lock(engine_->GetEngineHandle()); + return true; + } + return false; +} + +void EmoteDisplay::Unlock() +{ + if (engine_ && engine_->GetEngineHandle()) { + gfx_emote_unlock(engine_->GetEngineHandle()); + } +} + +} // namespace emote \ No newline at end of file diff --git a/main/display/emote_display.h b/main/display/emote_display.h new file mode 100644 index 0000000..ffa02a4 --- /dev/null +++ b/main/display/emote_display.h @@ -0,0 +1,102 @@ +#pragma once + +#include "display.h" +#include "lvgl_font.h" +#include +#include +#include +#include +#include +#include + +namespace emote { + +// Simple data structure for storing asset data without LVGL dependency +struct AssetData { + const void* data; + size_t size; + union { + uint8_t flags; // 1 byte for all animation flags + struct { + uint8_t fps : 6; // FPS (0-63) - 6 bits + uint8_t loop : 1; // Loop animation - 1 bit + uint8_t lack : 1; // Lack animation - 1 bit + }; + }; + + AssetData() : data(nullptr), size(0), flags(0) {} + AssetData(const void* d, size_t s) : data(d), size(s), flags(0) {} + AssetData(const void* d, size_t s, uint8_t f, bool l, bool k) + : data(d), size(s) + { + fps = f > 63 ? 63 : f; // 限制 FPS 到 6 位范围 + loop = l; + lack = k; + } +}; + +// Layout element data structure +struct LayoutData { + char align; // Store as char instead of string + int x; + int y; + int width; + int height; + bool has_size; + + LayoutData() : align(0), x(0), y(0), width(0), height(0), has_size(false) {} + LayoutData(char a, int x_pos, int y_pos, int w = 0, int h = 0) + : align(a), x(x_pos), y(y_pos), width(w), height(h), has_size(w > 0 && h > 0) {} +}; + +// Function to convert align string to GFX_ALIGN enum value +char StringToGfxAlign(const std::string &align_str); + +class EmoteEngine; + +class EmoteDisplay : public Display { +public: + EmoteDisplay(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io, int width, int height); + virtual ~EmoteDisplay(); + + virtual void SetEmotion(const char* emotion) override; + virtual void SetStatus(const char* status) override; + virtual void SetChatMessage(const char* role, const char* content) override; + virtual void SetTheme(Theme* theme) override; + virtual void ShowNotification(const char* notification, int duration_ms = 3000) override; + virtual void UpdateStatusBar(bool update_all = false) override; + virtual void SetPowerSaveMode(bool on) override; + virtual void SetPreviewImage(const void* image); + + void AddEmojiData(const std::string &name, const void* data, size_t size, uint8_t fps = 0, bool loop = false, bool lack = false); + void AddIconData(const std::string &name, const void* data, size_t size); + void AddLayoutData(const std::string &name, const std::string &align_str, int x, int y, int width = 0, int height = 0); + void AddTextFont(std::shared_ptr text_font); + AssetData GetEmojiData(const std::string &name) const; + AssetData GetIconData(const std::string &name) const; + + EmoteEngine* GetEngine() const; + void* GetEngineHandle() const; + + inline std::shared_ptr text_font() const + { + return text_font_; + } + +private: + void InitializeEngine(esp_lcd_panel_handle_t panel, esp_lcd_panel_io_handle_t panel_io, int width, int height); + virtual bool Lock(int timeout_ms = 0) override; + virtual void Unlock() override; + + std::unique_ptr engine_; + + // Font management + std::shared_ptr text_font_ = nullptr; + + // Non-LVGL asset data storage + std::map emoji_data_map_; + std::map icon_data_map_; + +}; + +} // namespace emote diff --git a/main/display/lcd_display.cc b/main/display/lcd_display.cc new file mode 100644 index 0000000..c00a8a7 --- /dev/null +++ b/main/display/lcd_display.cc @@ -0,0 +1,1196 @@ +#include "lcd_display.h" +#include "gif/lvgl_gif.h" +#include "settings.h" +#include "lvgl_theme.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "board.h" + +#define TAG "LcdDisplay" + +LV_FONT_DECLARE(BUILTIN_TEXT_FONT); +LV_FONT_DECLARE(BUILTIN_ICON_FONT); +LV_FONT_DECLARE(font_awesome_30_4); + +void LcdDisplay::InitializeLcdThemes() { + auto text_font = std::make_shared(&BUILTIN_TEXT_FONT); + auto icon_font = std::make_shared(&BUILTIN_ICON_FONT); + auto large_icon_font = std::make_shared(&font_awesome_30_4); + + // light theme + auto light_theme = new LvglTheme("light"); + light_theme->set_background_color(lv_color_hex(0xFFFFFF)); + light_theme->set_text_color(lv_color_hex(0x000000)); + light_theme->set_chat_background_color(lv_color_hex(0xE0E0E0)); + light_theme->set_user_bubble_color(lv_color_hex(0x00FF00)); + light_theme->set_assistant_bubble_color(lv_color_hex(0xDDDDDD)); + light_theme->set_system_bubble_color(lv_color_hex(0xFFFFFF)); + light_theme->set_system_text_color(lv_color_hex(0x000000)); + light_theme->set_border_color(lv_color_hex(0x000000)); + light_theme->set_low_battery_color(lv_color_hex(0x000000)); + light_theme->set_text_font(text_font); + light_theme->set_icon_font(icon_font); + light_theme->set_large_icon_font(large_icon_font); + + // dark theme + auto dark_theme = new LvglTheme("dark"); + dark_theme->set_background_color(lv_color_hex(0x000000)); + dark_theme->set_text_color(lv_color_hex(0xFFFFFF)); + dark_theme->set_chat_background_color(lv_color_hex(0x1F1F1F)); + dark_theme->set_user_bubble_color(lv_color_hex(0x00FF00)); + dark_theme->set_assistant_bubble_color(lv_color_hex(0x222222)); + dark_theme->set_system_bubble_color(lv_color_hex(0x000000)); + dark_theme->set_system_text_color(lv_color_hex(0xFFFFFF)); + dark_theme->set_border_color(lv_color_hex(0xFFFFFF)); + dark_theme->set_low_battery_color(lv_color_hex(0xFF0000)); + dark_theme->set_text_font(text_font); + dark_theme->set_icon_font(icon_font); + dark_theme->set_large_icon_font(large_icon_font); + + auto& theme_manager = LvglThemeManager::GetInstance(); + theme_manager.RegisterTheme("light", light_theme); + theme_manager.RegisterTheme("dark", dark_theme); +} + +LcdDisplay::LcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height) + : panel_io_(panel_io), panel_(panel) { + width_ = width; + height_ = height; + + // Initialize LCD themes + InitializeLcdThemes(); + + // Load theme from settings + Settings settings("display", false); + std::string theme_name = settings.GetString("theme", "light"); + current_theme_ = LvglThemeManager::GetInstance().GetTheme(theme_name); + + // Create a timer to hide the preview image + esp_timer_create_args_t preview_timer_args = { + .callback = [](void* arg) { + LcdDisplay* display = static_cast(arg); + display->SetPreviewImage(nullptr); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "preview_timer", + .skip_unhandled_events = false, + }; + esp_timer_create(&preview_timer_args, &preview_timer_); +} + +SpiLcdDisplay::SpiLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, bool mirror_x, bool mirror_y, bool swap_xy) + : LcdDisplay(panel_io, panel, width, height) { + + // draw white + std::vector buffer(width_, 0xFFFF); + for (int y = 0; y < height_; y++) { + esp_lcd_panel_draw_bitmap(panel_, 0, y, width_, y + 1, buffer.data()); + } + + // Set the display to on + ESP_LOGI(TAG, "Turning display on"); + { + esp_err_t __err = esp_lcd_panel_disp_on_off(panel_, true); + if (__err == ESP_ERR_NOT_SUPPORTED) { + ESP_LOGW(TAG, "Panel does not support disp_on_off; assuming ON"); + } else { + ESP_ERROR_CHECK(__err); + } + } + + ESP_LOGI(TAG, "Initialize LVGL library"); + lv_init(); + +#if CONFIG_SPIRAM + // lv image cache, currently only PNG is supported + size_t psram_size_mb = esp_psram_get_size() / 1024 / 1024; + if (psram_size_mb >= 8) { + lv_image_cache_resize(2 * 1024 * 1024, true); + ESP_LOGI(TAG, "Use 2MB of PSRAM for image cache"); + } else if (psram_size_mb >= 2) { + lv_image_cache_resize(512 * 1024, true); + ESP_LOGI(TAG, "Use 512KB of PSRAM for image cache"); + } +#endif + + ESP_LOGI(TAG, "Initialize LVGL port"); + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + port_cfg.task_priority = 1; +#if CONFIG_SOC_CPU_CORES_NUM > 1 + port_cfg.task_affinity = 1; +#endif + lvgl_port_init(&port_cfg); + + ESP_LOGI(TAG, "Adding LCD display"); + const lvgl_port_display_cfg_t display_cfg = { + .io_handle = panel_io_, + .panel_handle = panel_, + .control_handle = nullptr, + .buffer_size = static_cast(width_ * 20), + .double_buffer = false, + .trans_size = 0, + .hres = static_cast(width_), + .vres = static_cast(height_), + .monochrome = false, + .rotation = { + .swap_xy = swap_xy, + .mirror_x = mirror_x, + .mirror_y = mirror_y, + }, + .color_format = LV_COLOR_FORMAT_RGB565, + .flags = { + .buff_dma = 1, + .buff_spiram = 0, + .sw_rotate = 0, + .swap_bytes = 1, + .full_refresh = 0, + .direct_mode = 0, + }, + }; + + display_ = lvgl_port_add_disp(&display_cfg); + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add display"); + return; + } + + if (offset_x != 0 || offset_y != 0) { + lv_display_set_offset(display_, offset_x, offset_y); + } + + SetupUI(); +} + + +// RGB LCD implementation +RgbLcdDisplay::RgbLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy) + : LcdDisplay(panel_io, panel, width, height) { + + // draw white + std::vector buffer(width_, 0xFFFF); + for (int y = 0; y < height_; y++) { + esp_lcd_panel_draw_bitmap(panel_, 0, y, width_, y + 1, buffer.data()); + } + + ESP_LOGI(TAG, "Initialize LVGL library"); + lv_init(); + + ESP_LOGI(TAG, "Initialize LVGL port"); + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + port_cfg.task_priority = 1; + port_cfg.timer_period_ms = 50; + lvgl_port_init(&port_cfg); + + ESP_LOGI(TAG, "Adding LCD display"); + const lvgl_port_display_cfg_t display_cfg = { + .io_handle = panel_io_, + .panel_handle = panel_, + .buffer_size = static_cast(width_ * 20), + .double_buffer = true, + .hres = static_cast(width_), + .vres = static_cast(height_), + .rotation = { + .swap_xy = swap_xy, + .mirror_x = mirror_x, + .mirror_y = mirror_y, + }, + .flags = { + .buff_dma = 1, + .swap_bytes = 0, + .full_refresh = 1, + .direct_mode = 1, + }, + }; + + const lvgl_port_display_rgb_cfg_t rgb_cfg = { + .flags = { + .bb_mode = true, + .avoid_tearing = true, + } + }; + + display_ = lvgl_port_add_disp_rgb(&display_cfg, &rgb_cfg); + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add RGB display"); + return; + } + + if (offset_x != 0 || offset_y != 0) { + lv_display_set_offset(display_, offset_x, offset_y); + } + + SetupUI(); +} + +MipiLcdDisplay::MipiLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy) + : LcdDisplay(panel_io, panel, width, height) { + + ESP_LOGI(TAG, "Initialize LVGL library"); + lv_init(); + + ESP_LOGI(TAG, "Initialize LVGL port"); + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + lvgl_port_init(&port_cfg); + + ESP_LOGI(TAG, "Adding LCD display"); + const lvgl_port_display_cfg_t disp_cfg = { + .io_handle = panel_io, + .panel_handle = panel, + .control_handle = nullptr, + .buffer_size = static_cast(width_ * 50), + .double_buffer = false, + .hres = static_cast(width_), + .vres = static_cast(height_), + .monochrome = false, + /* Rotation values must be same as used in esp_lcd for initial settings of the screen */ + .rotation = { + .swap_xy = swap_xy, + .mirror_x = mirror_x, + .mirror_y = mirror_y, + }, + .flags = { + .buff_dma = true, + .buff_spiram =false, + .sw_rotate = true, + }, + }; + + const lvgl_port_display_dsi_cfg_t dpi_cfg = { + .flags = { + .avoid_tearing = false, + } + }; + display_ = lvgl_port_add_disp_dsi(&disp_cfg, &dpi_cfg); + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add display"); + return; + } + + if (offset_x != 0 || offset_y != 0) { + lv_display_set_offset(display_, offset_x, offset_y); + } + + SetupUI(); +} + +LcdDisplay::~LcdDisplay() { + SetPreviewImage(nullptr); + + // Clean up GIF controller + if (gif_controller_) { + gif_controller_->Stop(); + gif_controller_.reset(); + } + + if (preview_timer_ != nullptr) { + esp_timer_stop(preview_timer_); + esp_timer_delete(preview_timer_); + } + + if (preview_image_ != nullptr) { + lv_obj_del(preview_image_); + } + if (chat_message_label_ != nullptr) { + lv_obj_del(chat_message_label_); + } + if (emoji_label_ != nullptr) { + lv_obj_del(emoji_label_); + } + if (emoji_image_ != nullptr) { + lv_obj_del(emoji_image_); + } + if (emoji_box_ != nullptr) { + lv_obj_del(emoji_box_); + } + if (content_ != nullptr) { + lv_obj_del(content_); + } + if (bottom_bar_ != nullptr) { + lv_obj_del(bottom_bar_); + } + if (status_bar_ != nullptr) { + lv_obj_del(status_bar_); + } + if (top_bar_ != nullptr) { + lv_obj_del(top_bar_); + } + if (side_bar_ != nullptr) { + lv_obj_del(side_bar_); + } + if (container_ != nullptr) { + lv_obj_del(container_); + } + if (display_ != nullptr) { + lv_display_delete(display_); + } + + if (panel_ != nullptr) { + esp_lcd_panel_del(panel_); + } + if (panel_io_ != nullptr) { + esp_lcd_panel_io_del(panel_io_); + } +} + +bool LcdDisplay::Lock(int timeout_ms) { + return lvgl_port_lock(timeout_ms); +} + +void LcdDisplay::Unlock() { + lvgl_port_unlock(); +} + +#if CONFIG_USE_WECHAT_MESSAGE_STYLE +void LcdDisplay::SetupUI() { + DisplayLockGuard lock(this); + + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + auto large_icon_font = lvgl_theme->large_icon_font()->font(); + + auto screen = lv_screen_active(); + lv_obj_set_style_text_font(screen, text_font, 0); + lv_obj_set_style_text_color(screen, lvgl_theme->text_color(), 0); + lv_obj_set_style_bg_color(screen, lvgl_theme->background_color(), 0); + + /* Container */ + container_ = lv_obj_create(screen); + lv_obj_set_size(container_, LV_HOR_RES, LV_VER_RES); + lv_obj_set_style_radius(container_, 0, 0); + lv_obj_set_flex_flow(container_, LV_FLEX_FLOW_COLUMN); + lv_obj_set_style_pad_all(container_, 0, 0); + lv_obj_set_style_border_width(container_, 0, 0); + lv_obj_set_style_pad_row(container_, 0, 0); + lv_obj_set_style_bg_color(container_, lvgl_theme->background_color(), 0); + lv_obj_set_style_border_color(container_, lvgl_theme->border_color(), 0); + + /* Layer 1: Top bar - for status icons */ + top_bar_ = lv_obj_create(container_); + lv_obj_set_size(top_bar_, LV_HOR_RES, LV_SIZE_CONTENT); + lv_obj_set_style_radius(top_bar_, 0, 0); + lv_obj_set_style_bg_opa(top_bar_, LV_OPA_50, 0); // 50% opacity background + lv_obj_set_style_bg_color(top_bar_, lvgl_theme->background_color(), 0); + lv_obj_set_style_border_width(top_bar_, 0, 0); + lv_obj_set_style_pad_all(top_bar_, 0, 0); + lv_obj_set_style_pad_top(top_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_bottom(top_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_left(top_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_style_pad_right(top_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_flex_flow(top_bar_, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(top_bar_, LV_FLEX_ALIGN_SPACE_BETWEEN, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + lv_obj_set_scrollbar_mode(top_bar_, LV_SCROLLBAR_MODE_OFF); + + // Left icon + network_label_ = lv_label_create(top_bar_); + lv_label_set_text(network_label_, ""); + lv_obj_set_style_text_font(network_label_, icon_font, 0); + lv_obj_set_style_text_color(network_label_, lvgl_theme->text_color(), 0); + + // Right icons container + lv_obj_t* right_icons = lv_obj_create(top_bar_); + lv_obj_set_size(right_icons, LV_SIZE_CONTENT, LV_SIZE_CONTENT); + lv_obj_set_style_bg_opa(right_icons, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(right_icons, 0, 0); + lv_obj_set_style_pad_all(right_icons, 0, 0); + lv_obj_set_flex_flow(right_icons, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(right_icons, LV_FLEX_ALIGN_END, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + + mute_label_ = lv_label_create(right_icons); + lv_label_set_text(mute_label_, ""); + lv_obj_set_style_text_font(mute_label_, icon_font, 0); + lv_obj_set_style_text_color(mute_label_, lvgl_theme->text_color(), 0); + + battery_label_ = lv_label_create(right_icons); + lv_label_set_text(battery_label_, ""); + lv_obj_set_style_text_font(battery_label_, icon_font, 0); + lv_obj_set_style_text_color(battery_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_margin_left(battery_label_, lvgl_theme->spacing(2), 0); + + /* Layer 2: Status bar - for center text labels */ + status_bar_ = lv_obj_create(screen); + lv_obj_set_size(status_bar_, LV_HOR_RES, LV_SIZE_CONTENT); + lv_obj_set_style_radius(status_bar_, 0, 0); + lv_obj_set_style_bg_opa(status_bar_, LV_OPA_TRANSP, 0); // Transparent background + lv_obj_set_style_border_width(status_bar_, 0, 0); + lv_obj_set_style_pad_all(status_bar_, 0, 0); + lv_obj_set_style_pad_top(status_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_bottom(status_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_scrollbar_mode(status_bar_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_layout(status_bar_, LV_LAYOUT_NONE, 0); // Use absolute positioning + lv_obj_align(status_bar_, LV_ALIGN_TOP_MID, 0, 0); // Overlap with top_bar_ + + notification_label_ = lv_label_create(status_bar_); + lv_obj_set_width(notification_label_, LV_HOR_RES * 0.8); + lv_obj_set_style_text_align(notification_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_obj_set_style_text_color(notification_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(notification_label_, ""); + lv_obj_align(notification_label_, LV_ALIGN_CENTER, 0, 0); + lv_obj_add_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + + status_label_ = lv_label_create(status_bar_); + lv_obj_set_width(status_label_, LV_HOR_RES * 0.8); + lv_label_set_long_mode(status_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_obj_set_style_text_align(status_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_obj_set_style_text_color(status_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(status_label_, Lang::Strings::INITIALIZING); + lv_obj_align(status_label_, LV_ALIGN_CENTER, 0, 0); + + /* Content - Chat area */ + content_ = lv_obj_create(container_); + lv_obj_set_style_radius(content_, 0, 0); + lv_obj_set_width(content_, LV_HOR_RES); + lv_obj_set_flex_grow(content_, 1); + lv_obj_set_style_pad_all(content_, lvgl_theme->spacing(4), 0); + lv_obj_set_style_border_width(content_, 0, 0); + lv_obj_set_style_bg_color(content_, lvgl_theme->chat_background_color(), 0); // Background for chat area + + // Enable scrolling for chat content + lv_obj_set_scrollbar_mode(content_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_scroll_dir(content_, LV_DIR_VER); + + // Create a flex container for chat messages + lv_obj_set_flex_flow(content_, LV_FLEX_FLOW_COLUMN); + lv_obj_set_flex_align(content_, LV_FLEX_ALIGN_START, LV_FLEX_ALIGN_START, LV_FLEX_ALIGN_START); + lv_obj_set_style_pad_row(content_, lvgl_theme->spacing(4), 0); // Space between messages + + // We'll create chat messages dynamically in SetChatMessage + chat_message_label_ = nullptr; + + low_battery_popup_ = lv_obj_create(screen); + lv_obj_set_scrollbar_mode(low_battery_popup_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_size(low_battery_popup_, LV_HOR_RES * 0.9, text_font->line_height * 2); + lv_obj_align(low_battery_popup_, LV_ALIGN_BOTTOM_MID, 0, -lvgl_theme->spacing(4)); + lv_obj_set_style_bg_color(low_battery_popup_, lvgl_theme->low_battery_color(), 0); + lv_obj_set_style_radius(low_battery_popup_, lvgl_theme->spacing(4), 0); + low_battery_label_ = lv_label_create(low_battery_popup_); + lv_label_set_text(low_battery_label_, Lang::Strings::BATTERY_NEED_CHARGE); + lv_obj_set_style_text_color(low_battery_label_, lv_color_white(), 0); + lv_obj_center(low_battery_label_); + lv_obj_add_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN); + + emoji_image_ = lv_img_create(screen); + lv_obj_align(emoji_image_, LV_ALIGN_TOP_MID, 0, text_font->line_height + lvgl_theme->spacing(8)); + + // Display AI logo while booting + emoji_label_ = lv_label_create(screen); + lv_obj_center(emoji_label_); + lv_obj_set_style_text_font(emoji_label_, large_icon_font, 0); + lv_obj_set_style_text_color(emoji_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(emoji_label_, FONT_AWESOME_MICROCHIP_AI); +} +#if CONFIG_IDF_TARGET_ESP32P4 +#define MAX_MESSAGES 40 +#else +#define MAX_MESSAGES 20 +#endif +void LcdDisplay::SetChatMessage(const char* role, const char* content) { + DisplayLockGuard lock(this); + if (content_ == nullptr) { + return; + } + + // Check if message count exceeds limit + uint32_t child_count = lv_obj_get_child_cnt(content_); + if (child_count >= MAX_MESSAGES) { + // Delete the oldest message (first child object) + lv_obj_t* first_child = lv_obj_get_child(content_, 0); + lv_obj_t* last_child = lv_obj_get_child(content_, child_count - 1); + if (first_child != nullptr) { + lv_obj_del(first_child); + } + // Scroll to the last message immediately + if (last_child != nullptr) { + lv_obj_scroll_to_view_recursive(last_child, LV_ANIM_OFF); + } + } + + // Collapse system messages (if it's a system message, check if the last message is also a system message) + if (strcmp(role, "system") == 0) { + if (child_count > 0) { + // Get the last message container + lv_obj_t* last_container = lv_obj_get_child(content_, child_count - 1); + if (last_container != nullptr && lv_obj_get_child_cnt(last_container) > 0) { + // Get the bubble inside the container + lv_obj_t* last_bubble = lv_obj_get_child(last_container, 0); + if (last_bubble != nullptr) { + // Check if bubble type is system message + void* bubble_type_ptr = lv_obj_get_user_data(last_bubble); + if (bubble_type_ptr != nullptr && strcmp((const char*)bubble_type_ptr, "system") == 0) { + // If the last message is also a system message, delete it + lv_obj_del(last_container); + } + } + } + } + } else { + // Hide the centered AI logo + lv_obj_add_flag(emoji_label_, LV_OBJ_FLAG_HIDDEN); + } + + // Avoid empty message boxes + if(strlen(content) == 0) { + return; + } + + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + + // Create a message bubble + lv_obj_t* msg_bubble = lv_obj_create(content_); + lv_obj_set_style_radius(msg_bubble, 8, 0); + lv_obj_set_scrollbar_mode(msg_bubble, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_border_width(msg_bubble, 0, 0); + lv_obj_set_style_pad_all(msg_bubble, lvgl_theme->spacing(4), 0); + + // Create the message text + lv_obj_t* msg_text = lv_label_create(msg_bubble); + lv_label_set_text(msg_text, content); + + // Calculate actual text width + lv_coord_t text_width = lv_txt_get_width(content, strlen(content), text_font, 0); + + // Calculate bubble width + lv_coord_t max_width = LV_HOR_RES * 85 / 100 - 16; // 85% of screen width + lv_coord_t min_width = 20; + lv_coord_t bubble_width; + + // Ensure text width is not less than minimum width + if (text_width < min_width) { + text_width = min_width; + } + + // If text width is less than max width, use text width + if (text_width < max_width) { + bubble_width = text_width; + } else { + bubble_width = max_width; + } + + // Set message text width + lv_obj_set_width(msg_text, bubble_width); // Subtract padding + lv_label_set_long_mode(msg_text, LV_LABEL_LONG_WRAP); + + // Set bubble width + lv_obj_set_width(msg_bubble, bubble_width); + lv_obj_set_height(msg_bubble, LV_SIZE_CONTENT); + + // Set alignment and style based on message role + if (strcmp(role, "user") == 0) { + // User messages are right-aligned with green background + lv_obj_set_style_bg_color(msg_bubble, lvgl_theme->user_bubble_color(), 0); + lv_obj_set_style_bg_opa(msg_bubble, LV_OPA_70, 0); + // Set text color for contrast + lv_obj_set_style_text_color(msg_text, lvgl_theme->text_color(), 0); + + // Set custom attribute to mark bubble type + lv_obj_set_user_data(msg_bubble, (void*)"user"); + + // Set appropriate width for content + lv_obj_set_width(msg_bubble, LV_SIZE_CONTENT); + lv_obj_set_height(msg_bubble, LV_SIZE_CONTENT); + + // Don't grow + lv_obj_set_style_flex_grow(msg_bubble, 0, 0); + } else if (strcmp(role, "assistant") == 0) { + // Assistant messages are left-aligned with white background + lv_obj_set_style_bg_color(msg_bubble, lvgl_theme->assistant_bubble_color(), 0); + lv_obj_set_style_bg_opa(msg_bubble, LV_OPA_70, 0); + // Set text color for contrast + lv_obj_set_style_text_color(msg_text, lvgl_theme->text_color(), 0); + + // Set custom attribute to mark bubble type + lv_obj_set_user_data(msg_bubble, (void*)"assistant"); + + // Set appropriate width for content + lv_obj_set_width(msg_bubble, LV_SIZE_CONTENT); + lv_obj_set_height(msg_bubble, LV_SIZE_CONTENT); + + // Don't grow + lv_obj_set_style_flex_grow(msg_bubble, 0, 0); + } else if (strcmp(role, "system") == 0) { + // System messages are center-aligned with light gray background + lv_obj_set_style_bg_color(msg_bubble, lvgl_theme->system_bubble_color(), 0); + lv_obj_set_style_bg_opa(msg_bubble, LV_OPA_70, 0); + // Set text color for contrast + lv_obj_set_style_text_color(msg_text, lvgl_theme->system_text_color(), 0); + + // Set custom attribute to mark bubble type + lv_obj_set_user_data(msg_bubble, (void*)"system"); + + // Set appropriate width for content + lv_obj_set_width(msg_bubble, LV_SIZE_CONTENT); + lv_obj_set_height(msg_bubble, LV_SIZE_CONTENT); + + // Don't grow + lv_obj_set_style_flex_grow(msg_bubble, 0, 0); + } + + // Create a full-width container for user messages to ensure right alignment + if (strcmp(role, "user") == 0) { + // Create a full-width container + lv_obj_t* container = lv_obj_create(content_); + lv_obj_set_width(container, LV_HOR_RES); + lv_obj_set_height(container, LV_SIZE_CONTENT); + + // Make container transparent and borderless + lv_obj_set_style_bg_opa(container, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(container, 0, 0); + lv_obj_set_style_pad_all(container, 0, 0); + + // Move the message bubble into this container + lv_obj_set_parent(msg_bubble, container); + + // Right align the bubble in the container + lv_obj_align(msg_bubble, LV_ALIGN_RIGHT_MID, -25, 0); + + // Auto-scroll to this container + lv_obj_scroll_to_view_recursive(container, LV_ANIM_ON); + } else if (strcmp(role, "system") == 0) { + // Create full-width container for system messages to ensure center alignment + lv_obj_t* container = lv_obj_create(content_); + lv_obj_set_width(container, LV_HOR_RES); + lv_obj_set_height(container, LV_SIZE_CONTENT); + + lv_obj_set_style_bg_opa(container, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(container, 0, 0); + lv_obj_set_style_pad_all(container, 0, 0); + + lv_obj_set_parent(msg_bubble, container); + lv_obj_align(msg_bubble, LV_ALIGN_CENTER, 0, 0); + lv_obj_scroll_to_view_recursive(container, LV_ANIM_ON); + } else { + // For assistant messages + // Left align assistant messages + lv_obj_align(msg_bubble, LV_ALIGN_LEFT_MID, 0, 0); + + // Auto-scroll to the message bubble + lv_obj_scroll_to_view_recursive(msg_bubble, LV_ANIM_ON); + } + + // Store reference to the latest message label + chat_message_label_ = msg_text; +} + +void LcdDisplay::SetPreviewImage(std::unique_ptr image) { + DisplayLockGuard lock(this); + if (content_ == nullptr) { + return; + } + + if (image == nullptr) { + return; + } + + auto lvgl_theme = static_cast(current_theme_); + // Create a message bubble for image preview + lv_obj_t* img_bubble = lv_obj_create(content_); + lv_obj_set_style_radius(img_bubble, 8, 0); + lv_obj_set_scrollbar_mode(img_bubble, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_border_width(img_bubble, 0, 0); + lv_obj_set_style_pad_all(img_bubble, lvgl_theme->spacing(4), 0); + + // Set image bubble background color (similar to system message) + lv_obj_set_style_bg_color(img_bubble, lvgl_theme->assistant_bubble_color(), 0); + lv_obj_set_style_bg_opa(img_bubble, LV_OPA_70, 0); + + // Set custom attribute to mark bubble type + lv_obj_set_user_data(img_bubble, (void*)"image"); + + // Create the image object inside the bubble + lv_obj_t* preview_image = lv_image_create(img_bubble); + + // Calculate appropriate size for the image + lv_coord_t max_width = LV_HOR_RES * 70 / 100; // 70% of screen width + lv_coord_t max_height = LV_VER_RES * 50 / 100; // 50% of screen height + + // Calculate zoom factor to fit within maximum dimensions + auto img_dsc = image->image_dsc(); + lv_coord_t img_width = img_dsc->header.w; + lv_coord_t img_height = img_dsc->header.h; + if (img_width == 0 || img_height == 0) { + img_width = max_width; + img_height = max_height; + ESP_LOGW(TAG, "Invalid image dimensions: %ld x %ld, using default dimensions: %ld x %ld", img_width, img_height, max_width, max_height); + } + + lv_coord_t zoom_w = (max_width * 256) / img_width; + lv_coord_t zoom_h = (max_height * 256) / img_height; + lv_coord_t zoom = (zoom_w < zoom_h) ? zoom_w : zoom_h; + + // Ensure zoom doesn't exceed 256 (100%) + if (zoom > 256) zoom = 256; + + // Set image properties + lv_image_set_src(preview_image, img_dsc); + lv_image_set_scale(preview_image, zoom); + + // Add event handler to clean up LvglImage when image is deleted + // We need to transfer ownership of the unique_ptr to the event callback + LvglImage* raw_image = image.release(); // Release ownership of smart pointer + lv_obj_add_event_cb(preview_image, [](lv_event_t* e) { + LvglImage* img = (LvglImage*)lv_event_get_user_data(e); + if (img != nullptr) { + delete img; // Properly release memory by deleting LvglImage object + } + }, LV_EVENT_DELETE, (void*)raw_image); + + // Calculate actual scaled image dimensions + lv_coord_t scaled_width = (img_width * zoom) / 256; + lv_coord_t scaled_height = (img_height * zoom) / 256; + + // Set bubble size to be 16 pixels larger than the image (8 pixels on each side) + lv_obj_set_width(img_bubble, scaled_width + 16); + lv_obj_set_height(img_bubble, scaled_height + 16); + + // Don't grow in flex layout + lv_obj_set_style_flex_grow(img_bubble, 0, 0); + + // Center the image within the bubble + lv_obj_center(preview_image); + + // Left align the image bubble like assistant messages + lv_obj_align(img_bubble, LV_ALIGN_LEFT_MID, 0, 0); + + // Auto-scroll to the image bubble + lv_obj_scroll_to_view_recursive(img_bubble, LV_ANIM_ON); +} +#else +void LcdDisplay::SetupUI() { + DisplayLockGuard lock(this); + LvglTheme* lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + auto large_icon_font = lvgl_theme->large_icon_font()->font(); + + auto screen = lv_screen_active(); + lv_obj_set_style_text_font(screen, text_font, 0); + lv_obj_set_style_text_color(screen, lvgl_theme->text_color(), 0); + lv_obj_set_style_bg_color(screen, lvgl_theme->background_color(), 0); + + /* Container - used as background */ + container_ = lv_obj_create(screen); + lv_obj_set_size(container_, LV_HOR_RES, LV_VER_RES); + lv_obj_set_style_radius(container_, 0, 0); + lv_obj_set_style_pad_all(container_, 0, 0); + lv_obj_set_style_border_width(container_, 0, 0); + lv_obj_set_style_bg_color(container_, lvgl_theme->background_color(), 0); + lv_obj_set_style_border_color(container_, lvgl_theme->border_color(), 0); + + /* Bottom layer: emoji_box_ - centered display */ + emoji_box_ = lv_obj_create(screen); + lv_obj_set_size(emoji_box_, LV_SIZE_CONTENT, LV_SIZE_CONTENT); + lv_obj_set_style_bg_opa(emoji_box_, LV_OPA_TRANSP, 0); + lv_obj_set_style_pad_all(emoji_box_, 0, 0); + lv_obj_set_style_border_width(emoji_box_, 0, 0); + lv_obj_align(emoji_box_, LV_ALIGN_CENTER, 0, 0); + + emoji_label_ = lv_label_create(emoji_box_); + lv_obj_set_style_text_font(emoji_label_, large_icon_font, 0); + lv_obj_set_style_text_color(emoji_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(emoji_label_, FONT_AWESOME_MICROCHIP_AI); + + emoji_image_ = lv_img_create(emoji_box_); + lv_obj_center(emoji_image_); + lv_obj_add_flag(emoji_image_, LV_OBJ_FLAG_HIDDEN); + + /* Middle layer: preview_image_ - centered display */ + preview_image_ = lv_image_create(screen); + lv_obj_set_size(preview_image_, width_ / 2, height_ / 2); + lv_obj_align(preview_image_, LV_ALIGN_CENTER, 0, 0); + lv_obj_add_flag(preview_image_, LV_OBJ_FLAG_HIDDEN); + + /* Layer 1: Top bar - for status icons */ + top_bar_ = lv_obj_create(screen); + lv_obj_set_size(top_bar_, LV_HOR_RES, LV_SIZE_CONTENT); + lv_obj_set_style_radius(top_bar_, 0, 0); + lv_obj_set_style_bg_opa(top_bar_, LV_OPA_50, 0); // 50% opacity background + lv_obj_set_style_bg_color(top_bar_, lvgl_theme->background_color(), 0); + lv_obj_set_style_border_width(top_bar_, 0, 0); + lv_obj_set_style_pad_all(top_bar_, 0, 0); + lv_obj_set_style_pad_top(top_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_bottom(top_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_left(top_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_style_pad_right(top_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_flex_flow(top_bar_, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(top_bar_, LV_FLEX_ALIGN_SPACE_BETWEEN, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + lv_obj_set_scrollbar_mode(top_bar_, LV_SCROLLBAR_MODE_OFF); + lv_obj_align(top_bar_, LV_ALIGN_TOP_MID, 0, 0); + + // Left icon + network_label_ = lv_label_create(top_bar_); + lv_label_set_text(network_label_, ""); + lv_obj_set_style_text_font(network_label_, icon_font, 0); + lv_obj_set_style_text_color(network_label_, lvgl_theme->text_color(), 0); + + // Right icons container + lv_obj_t* right_icons = lv_obj_create(top_bar_); + lv_obj_set_size(right_icons, LV_SIZE_CONTENT, LV_SIZE_CONTENT); + lv_obj_set_style_bg_opa(right_icons, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(right_icons, 0, 0); + lv_obj_set_style_pad_all(right_icons, 0, 0); + lv_obj_set_flex_flow(right_icons, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(right_icons, LV_FLEX_ALIGN_END, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + + mute_label_ = lv_label_create(right_icons); + lv_label_set_text(mute_label_, ""); + lv_obj_set_style_text_font(mute_label_, icon_font, 0); + lv_obj_set_style_text_color(mute_label_, lvgl_theme->text_color(), 0); + + battery_label_ = lv_label_create(right_icons); + lv_label_set_text(battery_label_, ""); + lv_obj_set_style_text_font(battery_label_, icon_font, 0); + lv_obj_set_style_text_color(battery_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_margin_left(battery_label_, lvgl_theme->spacing(2), 0); + + /* Layer 2: Status bar - for center text labels */ + status_bar_ = lv_obj_create(screen); + lv_obj_set_size(status_bar_, LV_HOR_RES, LV_SIZE_CONTENT); + lv_obj_set_style_radius(status_bar_, 0, 0); + lv_obj_set_style_bg_opa(status_bar_, LV_OPA_TRANSP, 0); // Transparent background + lv_obj_set_style_border_width(status_bar_, 0, 0); + lv_obj_set_style_pad_all(status_bar_, 0, 0); + lv_obj_set_style_pad_top(status_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_bottom(status_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_scrollbar_mode(status_bar_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_layout(status_bar_, LV_LAYOUT_NONE, 0); // Use absolute positioning + lv_obj_align(status_bar_, LV_ALIGN_TOP_MID, 0, 0); // Overlap with top_bar_ + + notification_label_ = lv_label_create(status_bar_); + lv_obj_set_width(notification_label_, LV_HOR_RES * 0.75); + lv_obj_set_style_text_align(notification_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_obj_set_style_text_color(notification_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(notification_label_, ""); + lv_obj_align(notification_label_, LV_ALIGN_CENTER, 0, 0); + lv_obj_add_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + + status_label_ = lv_label_create(status_bar_); + lv_obj_set_width(status_label_, LV_HOR_RES * 0.75); + lv_label_set_long_mode(status_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_obj_set_style_text_align(status_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_obj_set_style_text_color(status_label_, lvgl_theme->text_color(), 0); + lv_label_set_text(status_label_, Lang::Strings::INITIALIZING); + lv_obj_align(status_label_, LV_ALIGN_CENTER, 0, 0); + + /* Top layer: Bottom bar - fixed at bottom, minimum height 48, height can be adaptive */ + bottom_bar_ = lv_obj_create(screen); + lv_obj_set_width(bottom_bar_, LV_HOR_RES); + lv_obj_set_height(bottom_bar_, LV_SIZE_CONTENT); + lv_obj_set_style_min_height(bottom_bar_, 48, 0); // Set minimum height 48 + lv_obj_set_style_radius(bottom_bar_, 0, 0); + lv_obj_set_style_bg_color(bottom_bar_, lvgl_theme->background_color(), 0); + lv_obj_set_style_text_color(bottom_bar_, lvgl_theme->text_color(), 0); + lv_obj_set_style_pad_top(bottom_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_bottom(bottom_bar_, lvgl_theme->spacing(2), 0); + lv_obj_set_style_pad_left(bottom_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_style_pad_right(bottom_bar_, lvgl_theme->spacing(4), 0); + lv_obj_set_style_border_width(bottom_bar_, 0, 0); + lv_obj_align(bottom_bar_, LV_ALIGN_BOTTOM_MID, 0, 0); + + /* chat_message_label_ placed in bottom_bar_ and vertically centered */ + chat_message_label_ = lv_label_create(bottom_bar_); + lv_label_set_text(chat_message_label_, ""); + lv_obj_set_width(chat_message_label_, LV_HOR_RES - lvgl_theme->spacing(8)); // Subtract left and right padding + lv_label_set_long_mode(chat_message_label_, LV_LABEL_LONG_WRAP); // Auto wrap mode + lv_obj_set_style_text_align(chat_message_label_, LV_TEXT_ALIGN_CENTER, 0); // Center text alignment + lv_obj_set_style_text_color(chat_message_label_, lvgl_theme->text_color(), 0); + lv_obj_align(chat_message_label_, LV_ALIGN_CENTER, 0, 0); // Vertically and horizontally centered in bottom_bar_ + + low_battery_popup_ = lv_obj_create(screen); + lv_obj_set_scrollbar_mode(low_battery_popup_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_size(low_battery_popup_, LV_HOR_RES * 0.9, text_font->line_height * 2); + lv_obj_align(low_battery_popup_, LV_ALIGN_BOTTOM_MID, 0, -lvgl_theme->spacing(4)); + lv_obj_set_style_bg_color(low_battery_popup_, lvgl_theme->low_battery_color(), 0); + lv_obj_set_style_radius(low_battery_popup_, lvgl_theme->spacing(4), 0); + + low_battery_label_ = lv_label_create(low_battery_popup_); + lv_label_set_text(low_battery_label_, Lang::Strings::BATTERY_NEED_CHARGE); + lv_obj_set_style_text_color(low_battery_label_, lv_color_white(), 0); + lv_obj_center(low_battery_label_); + lv_obj_add_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN); +} + +void LcdDisplay::SetPreviewImage(std::unique_ptr image) { + DisplayLockGuard lock(this); + if (preview_image_ == nullptr) { + ESP_LOGE(TAG, "Preview image is not initialized"); + return; + } + + if (image == nullptr) { + esp_timer_stop(preview_timer_); + lv_obj_remove_flag(emoji_box_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(preview_image_, LV_OBJ_FLAG_HIDDEN); + preview_image_cached_.reset(); + if (gif_controller_) { + gif_controller_->Start(); + } + return; + } + + preview_image_cached_ = std::move(image); + auto img_dsc = preview_image_cached_->image_dsc(); + lv_image_set_src(preview_image_, img_dsc); + if (img_dsc->header.w > 0 && img_dsc->header.h > 0) { + // zoom factor 0.5 + lv_image_set_scale(preview_image_, 128 * width_ / img_dsc->header.w); + } + + // Hide emoji_box_ + if (gif_controller_) { + gif_controller_->Stop(); + } + lv_obj_add_flag(emoji_box_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(preview_image_, LV_OBJ_FLAG_HIDDEN); + esp_timer_stop(preview_timer_); + ESP_ERROR_CHECK(esp_timer_start_once(preview_timer_, PREVIEW_IMAGE_DURATION_MS * 1000)); +} + +void LcdDisplay::SetChatMessage(const char* role, const char* content) { + DisplayLockGuard lock(this); + if (chat_message_label_ == nullptr) { + return; + } + lv_label_set_text(chat_message_label_, content); +} +#endif + +void LcdDisplay::SetEmotion(const char* emotion) { + // Stop any running GIF animation + if (gif_controller_) { + DisplayLockGuard lock(this); + gif_controller_->Stop(); + gif_controller_.reset(); + } + + if (emoji_image_ == nullptr) { + return; + } + + auto emoji_collection = static_cast(current_theme_)->emoji_collection(); + auto image = emoji_collection != nullptr ? emoji_collection->GetEmojiImage(emotion) : nullptr; + if (image == nullptr) { + const char* utf8 = font_awesome_get_utf8(emotion); + if (utf8 != nullptr && emoji_label_ != nullptr) { + DisplayLockGuard lock(this); + lv_label_set_text(emoji_label_, utf8); + lv_obj_add_flag(emoji_image_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(emoji_label_, LV_OBJ_FLAG_HIDDEN); + } + return; + } + + DisplayLockGuard lock(this); + if (image->IsGif()) { + // Create new GIF controller + gif_controller_ = std::make_unique(image->image_dsc()); + + if (gif_controller_->IsLoaded()) { + // Set up frame update callback + gif_controller_->SetFrameCallback([this]() { + lv_image_set_src(emoji_image_, gif_controller_->image_dsc()); + }); + + // Set initial frame and start animation + lv_image_set_src(emoji_image_, gif_controller_->image_dsc()); + gif_controller_->Start(); + + // Show GIF, hide others + lv_obj_add_flag(emoji_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(emoji_image_, LV_OBJ_FLAG_HIDDEN); + } else { + ESP_LOGE(TAG, "Failed to load GIF for emotion: %s", emotion); + gif_controller_.reset(); + } + } else { + lv_image_set_src(emoji_image_, image->image_dsc()); + lv_obj_add_flag(emoji_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(emoji_image_, LV_OBJ_FLAG_HIDDEN); + } + +#if CONFIG_USE_WECHAT_MESSAGE_STYLE + // In WeChat message style, if emotion is neutral, don't display it + uint32_t child_count = lv_obj_get_child_cnt(content_); + if (strcmp(emotion, "neutral") == 0 && child_count > 0) { + // Stop GIF animation if running + if (gif_controller_) { + gif_controller_->Stop(); + gif_controller_.reset(); + } + + lv_obj_add_flag(emoji_image_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(emoji_label_, LV_OBJ_FLAG_HIDDEN); + } +#endif +} + +void LcdDisplay::SetTheme(Theme* theme) { + DisplayLockGuard lock(this); + + auto lvgl_theme = static_cast(theme); + + // Get the active screen + lv_obj_t* screen = lv_screen_active(); + + // Set font + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + auto large_icon_font = lvgl_theme->large_icon_font()->font(); + + if (text_font->line_height >= 40) { + lv_obj_set_style_text_font(mute_label_, large_icon_font, 0); + lv_obj_set_style_text_font(battery_label_, large_icon_font, 0); + lv_obj_set_style_text_font(network_label_, large_icon_font, 0); + } else { + lv_obj_set_style_text_font(mute_label_, icon_font, 0); + lv_obj_set_style_text_font(battery_label_, icon_font, 0); + lv_obj_set_style_text_font(network_label_, icon_font, 0); + } + + // Set parent text color + lv_obj_set_style_text_font(screen, text_font, 0); + lv_obj_set_style_text_color(screen, lvgl_theme->text_color(), 0); + + // Set background image + if (lvgl_theme->background_image() != nullptr) { + lv_obj_set_style_bg_image_src(container_, lvgl_theme->background_image()->image_dsc(), 0); + } else { + lv_obj_set_style_bg_image_src(container_, nullptr, 0); + lv_obj_set_style_bg_color(container_, lvgl_theme->background_color(), 0); + } + + // Update top bar background color with 50% opacity + if (top_bar_ != nullptr) { + lv_obj_set_style_bg_opa(top_bar_, LV_OPA_50, 0); + lv_obj_set_style_bg_color(top_bar_, lvgl_theme->background_color(), 0); + } + + // Update status bar elements + lv_obj_set_style_text_color(network_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_text_color(status_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_text_color(notification_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_text_color(mute_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_text_color(battery_label_, lvgl_theme->text_color(), 0); + lv_obj_set_style_text_color(emoji_label_, lvgl_theme->text_color(), 0); + + // If we have the chat message style, update all message bubbles +#if CONFIG_USE_WECHAT_MESSAGE_STYLE + // Set content background opacity + lv_obj_set_style_bg_opa(content_, LV_OPA_TRANSP, 0); + + // Iterate through all children of content (message containers or bubbles) + uint32_t child_count = lv_obj_get_child_cnt(content_); + for (uint32_t i = 0; i < child_count; i++) { + lv_obj_t* obj = lv_obj_get_child(content_, i); + if (obj == nullptr) continue; + + lv_obj_t* bubble = nullptr; + + // Check if this object is a container or bubble + // If it's a container (user or system message), get its child as bubble + // If it's a bubble (assistant message), use it directly + if (lv_obj_get_child_cnt(obj) > 0) { + // Might be a container, check if it's a user or system message container + // User and system message containers are transparent + lv_opa_t bg_opa = lv_obj_get_style_bg_opa(obj, 0); + if (bg_opa == LV_OPA_TRANSP) { + // This is a user or system message container + bubble = lv_obj_get_child(obj, 0); + } else { + // This might be an assistant message bubble itself + bubble = obj; + } + } else { + // No child elements, might be other UI elements, skip + continue; + } + + if (bubble == nullptr) continue; + + // Use saved user data to identify bubble type + void* bubble_type_ptr = lv_obj_get_user_data(bubble); + if (bubble_type_ptr != nullptr) { + const char* bubble_type = static_cast(bubble_type_ptr); + + // Apply correct color based on bubble type + if (strcmp(bubble_type, "user") == 0) { + lv_obj_set_style_bg_color(bubble, lvgl_theme->user_bubble_color(), 0); + } else if (strcmp(bubble_type, "assistant") == 0) { + lv_obj_set_style_bg_color(bubble, lvgl_theme->assistant_bubble_color(), 0); + } else if (strcmp(bubble_type, "system") == 0) { + lv_obj_set_style_bg_color(bubble, lvgl_theme->system_bubble_color(), 0); + } else if (strcmp(bubble_type, "image") == 0) { + lv_obj_set_style_bg_color(bubble, lvgl_theme->system_bubble_color(), 0); + } + + // Update border color + lv_obj_set_style_border_color(bubble, lvgl_theme->border_color(), 0); + + // Update text color for the message + if (lv_obj_get_child_cnt(bubble) > 0) { + lv_obj_t* text = lv_obj_get_child(bubble, 0); + if (text != nullptr) { + // Set text color based on bubble type + if (strcmp(bubble_type, "system") == 0) { + lv_obj_set_style_text_color(text, lvgl_theme->system_text_color(), 0); + } else { + lv_obj_set_style_text_color(text, lvgl_theme->text_color(), 0); + } + } + } + } else { + ESP_LOGW(TAG, "child[%lu] Bubble type is not found", i); + } + } +#else + // Simple UI mode - just update the main chat message + if (chat_message_label_ != nullptr) { + lv_obj_set_style_text_color(chat_message_label_, lvgl_theme->text_color(), 0); + } + + if (emoji_label_ != nullptr) { + lv_obj_set_style_text_color(emoji_label_, lvgl_theme->text_color(), 0); + } + + // Update bottom bar background color with 50% opacity + if (bottom_bar_ != nullptr) { + lv_obj_set_style_bg_opa(bottom_bar_, LV_OPA_50, 0); + lv_obj_set_style_bg_color(bottom_bar_, lvgl_theme->background_color(), 0); + } +#endif + + // Update low battery popup + lv_obj_set_style_bg_color(low_battery_popup_, lvgl_theme->low_battery_color(), 0); + + // No errors occurred. Save theme to settings + Display::SetTheme(lvgl_theme); +} + +void LcdDisplay::SetHideSubtitle(bool hide) { + DisplayLockGuard lock(this); + hide_subtitle_ = hide; + + // Immediately update UI visibility based on the setting + if (bottom_bar_ != nullptr) { + if (hide) { + lv_obj_add_flag(bottom_bar_, LV_OBJ_FLAG_HIDDEN); + } else { + lv_obj_remove_flag(bottom_bar_, LV_OBJ_FLAG_HIDDEN); + } + } +} diff --git a/main/display/lcd_display.h b/main/display/lcd_display.h new file mode 100644 index 0000000..1dc2a8d --- /dev/null +++ b/main/display/lcd_display.h @@ -0,0 +1,85 @@ +#ifndef LCD_DISPLAY_H +#define LCD_DISPLAY_H + +#include "lvgl_display.h" +#include "gif/lvgl_gif.h" + +#include +#include +#include + +#include +#include + +#define PREVIEW_IMAGE_DURATION_MS 5000 + + +class LcdDisplay : public LvglDisplay { +protected: + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + lv_draw_buf_t draw_buf_; + lv_obj_t* top_bar_ = nullptr; + lv_obj_t* status_bar_ = nullptr; + lv_obj_t* content_ = nullptr; + lv_obj_t* container_ = nullptr; + lv_obj_t* side_bar_ = nullptr; + lv_obj_t* bottom_bar_ = nullptr; + lv_obj_t* preview_image_ = nullptr; + lv_obj_t* emoji_label_ = nullptr; + lv_obj_t* emoji_image_ = nullptr; + std::unique_ptr gif_controller_ = nullptr; + lv_obj_t* emoji_box_ = nullptr; + lv_obj_t* chat_message_label_ = nullptr; + esp_timer_handle_t preview_timer_ = nullptr; + std::unique_ptr preview_image_cached_ = nullptr; + bool hide_subtitle_ = false; // Control whether to hide chat messages/subtitles + + void InitializeLcdThemes(); + void SetupUI(); + virtual bool Lock(int timeout_ms = 0) override; + virtual void Unlock() override; + +protected: + // Add protected constructor + LcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height); + +public: + ~LcdDisplay(); + virtual void SetEmotion(const char* emotion) override; + virtual void SetChatMessage(const char* role, const char* content) override; + virtual void SetPreviewImage(std::unique_ptr image) override; + + // Add theme switching function + virtual void SetTheme(Theme* theme) override; + + // Set whether to hide chat messages/subtitles + void SetHideSubtitle(bool hide); +}; + +// SPI LCD display +class SpiLcdDisplay : public LcdDisplay { +public: + SpiLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy); +}; + +// RGB LCD display +class RgbLcdDisplay : public LcdDisplay { +public: + RgbLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy); +}; + +// MIPI LCD display +class MipiLcdDisplay : public LcdDisplay { +public: + MipiLcdDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, int offset_x, int offset_y, + bool mirror_x, bool mirror_y, bool swap_xy); +}; + +#endif // LCD_DISPLAY_H diff --git a/main/display/lvgl_display/emoji_collection.cc b/main/display/lvgl_display/emoji_collection.cc new file mode 100644 index 0000000..c9a1a60 --- /dev/null +++ b/main/display/lvgl_display/emoji_collection.cc @@ -0,0 +1,123 @@ +#include "emoji_collection.h" + +#include +#include +#include + +#define TAG "EmojiCollection" + +void EmojiCollection::AddEmoji(const std::string& name, LvglImage* image) { + emoji_collection_[name] = image; +} + +const LvglImage* EmojiCollection::GetEmojiImage(const char* name) { + auto it = emoji_collection_.find(name); + if (it != emoji_collection_.end()) { + return it->second; + } + + ESP_LOGW(TAG, "Emoji not found: %s", name); + return nullptr; +} + +EmojiCollection::~EmojiCollection() { + for (auto it = emoji_collection_.begin(); it != emoji_collection_.end(); ++it) { + delete it->second; + } + emoji_collection_.clear(); +} + +// These are declared in xiaozhi-fonts/src/font_emoji_32.c +extern const lv_image_dsc_t emoji_1f636_32; // neutral +extern const lv_image_dsc_t emoji_1f642_32; // happy +extern const lv_image_dsc_t emoji_1f606_32; // laughing +extern const lv_image_dsc_t emoji_1f602_32; // funny +extern const lv_image_dsc_t emoji_1f614_32; // sad +extern const lv_image_dsc_t emoji_1f620_32; // angry +extern const lv_image_dsc_t emoji_1f62d_32; // crying +extern const lv_image_dsc_t emoji_1f60d_32; // loving +extern const lv_image_dsc_t emoji_1f633_32; // embarrassed +extern const lv_image_dsc_t emoji_1f62f_32; // surprised +extern const lv_image_dsc_t emoji_1f631_32; // shocked +extern const lv_image_dsc_t emoji_1f914_32; // thinking +extern const lv_image_dsc_t emoji_1f609_32; // winking +extern const lv_image_dsc_t emoji_1f60e_32; // cool +extern const lv_image_dsc_t emoji_1f60c_32; // relaxed +extern const lv_image_dsc_t emoji_1f924_32; // delicious +extern const lv_image_dsc_t emoji_1f618_32; // kissy +extern const lv_image_dsc_t emoji_1f60f_32; // confident +extern const lv_image_dsc_t emoji_1f634_32; // sleepy +extern const lv_image_dsc_t emoji_1f61c_32; // silly +extern const lv_image_dsc_t emoji_1f644_32; // confused + +Twemoji32::Twemoji32() { + AddEmoji("neutral", new LvglSourceImage(&emoji_1f636_32)); + AddEmoji("happy", new LvglSourceImage(&emoji_1f642_32)); + AddEmoji("laughing", new LvglSourceImage(&emoji_1f606_32)); + AddEmoji("funny", new LvglSourceImage(&emoji_1f602_32)); + AddEmoji("sad", new LvglSourceImage(&emoji_1f614_32)); + AddEmoji("angry", new LvglSourceImage(&emoji_1f620_32)); + AddEmoji("crying", new LvglSourceImage(&emoji_1f62d_32)); + AddEmoji("loving", new LvglSourceImage(&emoji_1f60d_32)); + AddEmoji("embarrassed", new LvglSourceImage(&emoji_1f633_32)); + AddEmoji("surprised", new LvglSourceImage(&emoji_1f62f_32)); + AddEmoji("shocked", new LvglSourceImage(&emoji_1f631_32)); + AddEmoji("thinking", new LvglSourceImage(&emoji_1f914_32)); + AddEmoji("winking", new LvglSourceImage(&emoji_1f609_32)); + AddEmoji("cool", new LvglSourceImage(&emoji_1f60e_32)); + AddEmoji("relaxed", new LvglSourceImage(&emoji_1f60c_32)); + AddEmoji("delicious", new LvglSourceImage(&emoji_1f924_32)); + AddEmoji("kissy", new LvglSourceImage(&emoji_1f618_32)); + AddEmoji("confident", new LvglSourceImage(&emoji_1f60f_32)); + AddEmoji("sleepy", new LvglSourceImage(&emoji_1f634_32)); + AddEmoji("silly", new LvglSourceImage(&emoji_1f61c_32)); + AddEmoji("confused", new LvglSourceImage(&emoji_1f644_32)); +} + + +// These are declared in xiaozhi-fonts/src/font_emoji_64.c +extern const lv_image_dsc_t emoji_1f636_64; // neutral +extern const lv_image_dsc_t emoji_1f642_64; // happy +extern const lv_image_dsc_t emoji_1f606_64; // laughing +extern const lv_image_dsc_t emoji_1f602_64; // funny +extern const lv_image_dsc_t emoji_1f614_64; // sad +extern const lv_image_dsc_t emoji_1f620_64; // angry +extern const lv_image_dsc_t emoji_1f62d_64; // crying +extern const lv_image_dsc_t emoji_1f60d_64; // loving +extern const lv_image_dsc_t emoji_1f633_64; // embarrassed +extern const lv_image_dsc_t emoji_1f62f_64; // surprised +extern const lv_image_dsc_t emoji_1f631_64; // shocked +extern const lv_image_dsc_t emoji_1f914_64; // thinking +extern const lv_image_dsc_t emoji_1f609_64; // winking +extern const lv_image_dsc_t emoji_1f60e_64; // cool +extern const lv_image_dsc_t emoji_1f60c_64; // relaxed +extern const lv_image_dsc_t emoji_1f924_64; // delicious +extern const lv_image_dsc_t emoji_1f618_64; // kissy +extern const lv_image_dsc_t emoji_1f60f_64; // confident +extern const lv_image_dsc_t emoji_1f634_64; // sleepy +extern const lv_image_dsc_t emoji_1f61c_64; // silly +extern const lv_image_dsc_t emoji_1f644_64; // confused + +Twemoji64::Twemoji64() { + AddEmoji("neutral", new LvglSourceImage(&emoji_1f636_64)); + AddEmoji("happy", new LvglSourceImage(&emoji_1f642_64)); + AddEmoji("laughing", new LvglSourceImage(&emoji_1f606_64)); + AddEmoji("funny", new LvglSourceImage(&emoji_1f602_64)); + AddEmoji("sad", new LvglSourceImage(&emoji_1f614_64)); + AddEmoji("angry", new LvglSourceImage(&emoji_1f620_64)); + AddEmoji("crying", new LvglSourceImage(&emoji_1f62d_64)); + AddEmoji("loving", new LvglSourceImage(&emoji_1f60d_64)); + AddEmoji("embarrassed", new LvglSourceImage(&emoji_1f633_64)); + AddEmoji("surprised", new LvglSourceImage(&emoji_1f62f_64)); + AddEmoji("shocked", new LvglSourceImage(&emoji_1f631_64)); + AddEmoji("thinking", new LvglSourceImage(&emoji_1f914_64)); + AddEmoji("winking", new LvglSourceImage(&emoji_1f609_64)); + AddEmoji("cool", new LvglSourceImage(&emoji_1f60e_64)); + AddEmoji("relaxed", new LvglSourceImage(&emoji_1f60c_64)); + AddEmoji("delicious", new LvglSourceImage(&emoji_1f924_64)); + AddEmoji("kissy", new LvglSourceImage(&emoji_1f618_64)); + AddEmoji("confident", new LvglSourceImage(&emoji_1f60f_64)); + AddEmoji("sleepy", new LvglSourceImage(&emoji_1f634_64)); + AddEmoji("silly", new LvglSourceImage(&emoji_1f61c_64)); + AddEmoji("confused", new LvglSourceImage(&emoji_1f644_64)); +} diff --git a/main/display/lvgl_display/emoji_collection.h b/main/display/lvgl_display/emoji_collection.h new file mode 100644 index 0000000..c9eac05 --- /dev/null +++ b/main/display/lvgl_display/emoji_collection.h @@ -0,0 +1,34 @@ +#ifndef EMOJI_COLLECTION_H +#define EMOJI_COLLECTION_H + +#include "lvgl_image.h" + +#include + +#include +#include +#include + + +// Define interface for emoji collection +class EmojiCollection { +public: + virtual void AddEmoji(const std::string& name, LvglImage* image); + virtual const LvglImage* GetEmojiImage(const char* name); + virtual ~EmojiCollection(); + +private: + std::map emoji_collection_; +}; + +class Twemoji32 : public EmojiCollection { +public: + Twemoji32(); +}; + +class Twemoji64 : public EmojiCollection { +public: + Twemoji64(); +}; + +#endif diff --git a/main/display/lvgl_display/gif/LICENSE.txt b/main/display/lvgl_display/gif/LICENSE.txt new file mode 100644 index 0000000..c53d519 --- /dev/null +++ b/main/display/lvgl_display/gif/LICENSE.txt @@ -0,0 +1,2 @@ +All of the source code and documentation for gifdec is released into the +public domain and provided without warranty of any kind. diff --git a/main/display/lvgl_display/gif/README.md b/main/display/lvgl_display/gif/README.md new file mode 100644 index 0000000..935cfeb --- /dev/null +++ b/main/display/lvgl_display/gif/README.md @@ -0,0 +1,17 @@ +# 说明 / Description + +## 中文 + +本目录代码移植自 LVGL 的 GIF 程序。 + +主要修复和改进: +- 修复了透明背景问题 +- 兼容了 87a 版本的 GIF 格式 + +## English + +The code in this directory is ported from LVGL's GIF program. + +Main fixes and improvements: +- Fixed transparent background issues +- Added compatibility for GIF 87a version format diff --git a/main/display/lvgl_display/gif/gifdec.c b/main/display/lvgl_display/gif/gifdec.c new file mode 100644 index 0000000..1e74aab --- /dev/null +++ b/main/display/lvgl_display/gif/gifdec.c @@ -0,0 +1,821 @@ +#include "gifdec.h" + +#include +#include +#include +#include + +#define TAG "GIF" + +#define MIN(A, B) ((A) < (B) ? (A) : (B)) +#define MAX(A, B) ((A) > (B) ? (A) : (B)) + +typedef struct Entry { + uint16_t length; + uint16_t prefix; + uint8_t suffix; +} Entry; + +typedef struct Table { + int bulk; + int nentries; + Entry * entries; +} Table; + +#if LV_GIF_CACHE_DECODE_DATA +#define LZW_MAXBITS 12 +#define LZW_TABLE_SIZE (1 << LZW_MAXBITS) +#define LZW_CACHE_SIZE (LZW_TABLE_SIZE * 4) +#endif + +static gd_GIF * gif_open(gd_GIF * gif); +static bool f_gif_open(gd_GIF * gif, const void * path, bool is_file); +static void f_gif_read(gd_GIF * gif, void * buf, size_t len); +static int f_gif_seek(gd_GIF * gif, size_t pos, int k); +static void f_gif_close(gd_GIF * gif); + +#if LV_USE_DRAW_SW_ASM == LV_DRAW_SW_ASM_HELIUM + #include "gifdec_mve.h" +#endif + +static uint16_t +read_num(gd_GIF * gif) +{ + uint8_t bytes[2]; + + f_gif_read(gif, bytes, 2); + return bytes[0] + (((uint16_t) bytes[1]) << 8); +} + +gd_GIF * +gd_open_gif_file(const char * fname) +{ + gd_GIF gif_base; + memset(&gif_base, 0, sizeof(gif_base)); + + bool res = f_gif_open(&gif_base, fname, true); + if(!res) return NULL; + + return gif_open(&gif_base); +} + +gd_GIF * +gd_open_gif_data(const void * data) +{ + gd_GIF gif_base; + memset(&gif_base, 0, sizeof(gif_base)); + + bool res = f_gif_open(&gif_base, data, false); + if(!res) return NULL; + + return gif_open(&gif_base); +} + +static gd_GIF * gif_open(gd_GIF * gif_base) +{ + uint8_t sigver[3]; + uint16_t width, height, depth; + uint8_t fdsz, bgidx, aspect; + uint8_t * bgcolor; + int gct_sz; + gd_GIF * gif = NULL; + + /* Header */ + f_gif_read(gif_base, sigver, 3); + if(memcmp(sigver, "GIF", 3) != 0) { + ESP_LOGW(TAG, "invalid signature"); + goto fail; + } + /* Version */ + f_gif_read(gif_base, sigver, 3); + if(memcmp(sigver, "89a", 3) != 0 && memcmp(sigver, "87a", 3) != 0) { + ESP_LOGW(TAG, "invalid version"); + goto fail; + } + /* Width x Height */ + width = read_num(gif_base); + height = read_num(gif_base); + /* FDSZ */ + f_gif_read(gif_base, &fdsz, 1); + /* Presence of GCT */ + if(!(fdsz & 0x80)) { + ESP_LOGW(TAG, "no global color table"); + goto fail; + } + /* Color Space's Depth */ + depth = ((fdsz >> 4) & 7) + 1; + /* Ignore Sort Flag. */ + /* GCT Size */ + gct_sz = 1 << ((fdsz & 0x07) + 1); + /* Background Color Index */ + f_gif_read(gif_base, &bgidx, 1); + /* Aspect Ratio */ + f_gif_read(gif_base, &aspect, 1); + /* Create gd_GIF Structure. */ + if(0 == width || 0 == height){ + ESP_LOGW(TAG, "Zero size image"); + goto fail; + } +#if LV_GIF_CACHE_DECODE_DATA + if(0 == (INT_MAX - sizeof(gd_GIF) - LZW_CACHE_SIZE) / width / height / 5){ + ESP_LOGW(TAG, "Image dimensions are too large"); + goto fail; + } + gif = lv_malloc(sizeof(gd_GIF) + 5 * width * height + LZW_CACHE_SIZE); +#else + if(0 == (INT_MAX - sizeof(gd_GIF)) / width / height / 5){ + ESP_LOGW(TAG, "Image dimensions are too large"); + goto fail; + } + gif = lv_malloc(sizeof(gd_GIF) + 5 * width * height); +#endif + if(!gif) goto fail; + memcpy(gif, gif_base, sizeof(gd_GIF)); + gif->width = width; + gif->height = height; + gif->depth = depth; + /* Read GCT */ + gif->gct.size = gct_sz; + f_gif_read(gif, gif->gct.colors, 3 * gif->gct.size); + gif->palette = &gif->gct; + gif->bgindex = bgidx; + gif->canvas = (uint8_t *) &gif[1]; + gif->frame = &gif->canvas[4 * width * height]; + if(gif->bgindex) { + memset(gif->frame, gif->bgindex, gif->width * gif->height); + } + bgcolor = &gif->palette->colors[gif->bgindex * 3]; + #if LV_GIF_CACHE_DECODE_DATA + gif->lzw_cache = gif->frame + width * height; + #endif + +#ifdef GIFDEC_FILL_BG + GIFDEC_FILL_BG(gif->canvas, gif->width * gif->height, 1, gif->width * gif->height, bgcolor, 0x00); +#else + for(int i = 0; i < gif->width * gif->height; i++) { + gif->canvas[i * 4 + 0] = *(bgcolor + 2); + gif->canvas[i * 4 + 1] = *(bgcolor + 1); + gif->canvas[i * 4 + 2] = *(bgcolor + 0); + gif->canvas[i * 4 + 3] = 0x00; // 初始化为透明,让第一帧根据自己的透明度设置来渲染 + } +#endif + gif->anim_start = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + gif->loop_count = -1; + goto ok; +fail: + f_gif_close(gif_base); +ok: + return gif; +} + +static void +discard_sub_blocks(gd_GIF * gif) +{ + uint8_t size; + + do { + f_gif_read(gif, &size, 1); + f_gif_seek(gif, size, LV_FS_SEEK_CUR); + } while(size); +} + +static void +read_plain_text_ext(gd_GIF * gif) +{ + if(gif->plain_text) { + uint16_t tx, ty, tw, th; + uint8_t cw, ch, fg, bg; + size_t sub_block; + f_gif_seek(gif, 1, LV_FS_SEEK_CUR); /* block size = 12 */ + tx = read_num(gif); + ty = read_num(gif); + tw = read_num(gif); + th = read_num(gif); + f_gif_read(gif, &cw, 1); + f_gif_read(gif, &ch, 1); + f_gif_read(gif, &fg, 1); + f_gif_read(gif, &bg, 1); + sub_block = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + gif->plain_text(gif, tx, ty, tw, th, cw, ch, fg, bg); + f_gif_seek(gif, sub_block, LV_FS_SEEK_SET); + } + else { + /* Discard plain text metadata. */ + f_gif_seek(gif, 13, LV_FS_SEEK_CUR); + } + /* Discard plain text sub-blocks. */ + discard_sub_blocks(gif); +} + +static void +read_graphic_control_ext(gd_GIF * gif) +{ + uint8_t rdit; + + /* Discard block size (always 0x04). */ + f_gif_seek(gif, 1, LV_FS_SEEK_CUR); + f_gif_read(gif, &rdit, 1); + gif->gce.disposal = (rdit >> 2) & 3; + gif->gce.input = rdit & 2; + gif->gce.transparency = rdit & 1; + gif->gce.delay = read_num(gif); + f_gif_read(gif, &gif->gce.tindex, 1); + /* Skip block terminator. */ + f_gif_seek(gif, 1, LV_FS_SEEK_CUR); +} + +static void +read_comment_ext(gd_GIF * gif) +{ + if(gif->comment) { + size_t sub_block = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + gif->comment(gif); + f_gif_seek(gif, sub_block, LV_FS_SEEK_SET); + } + /* Discard comment sub-blocks. */ + discard_sub_blocks(gif); +} + +static void +read_application_ext(gd_GIF * gif) +{ + char app_id[8]; + char app_auth_code[3]; + uint16_t loop_count; + + /* Discard block size (always 0x0B). */ + f_gif_seek(gif, 1, LV_FS_SEEK_CUR); + /* Application Identifier. */ + f_gif_read(gif, app_id, 8); + /* Application Authentication Code. */ + f_gif_read(gif, app_auth_code, 3); + if(!strncmp(app_id, "NETSCAPE", sizeof(app_id))) { + /* Discard block size (0x03) and constant byte (0x01). */ + f_gif_seek(gif, 2, LV_FS_SEEK_CUR); + loop_count = read_num(gif); + if(gif->loop_count < 0) { + if(loop_count == 0) { + gif->loop_count = 0; + } + else { + gif->loop_count = loop_count + 1; + } + } + /* Skip block terminator. */ + f_gif_seek(gif, 1, LV_FS_SEEK_CUR); + } + else if(gif->application) { + size_t sub_block = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + gif->application(gif, app_id, app_auth_code); + f_gif_seek(gif, sub_block, LV_FS_SEEK_SET); + discard_sub_blocks(gif); + } + else { + discard_sub_blocks(gif); + } +} + +static void +read_ext(gd_GIF * gif) +{ + uint8_t label; + + f_gif_read(gif, &label, 1); + switch(label) { + case 0x01: + read_plain_text_ext(gif); + break; + case 0xF9: + read_graphic_control_ext(gif); + break; + case 0xFE: + read_comment_ext(gif); + break; + case 0xFF: + read_application_ext(gif); + break; + default: + ESP_LOGW(TAG, "unknown extension: %02X\n", label); + } +} + +static uint16_t +get_key(gd_GIF *gif, int key_size, uint8_t *sub_len, uint8_t *shift, uint8_t *byte) +{ + int bits_read; + int rpad; + int frag_size; + uint16_t key; + + key = 0; + for (bits_read = 0; bits_read < key_size; bits_read += frag_size) { + rpad = (*shift + bits_read) % 8; + if (rpad == 0) { + /* Update byte. */ + if (*sub_len == 0) { + f_gif_read(gif, sub_len, 1); /* Must be nonzero! */ + if (*sub_len == 0) return 0x1000; + } + f_gif_read(gif, byte, 1); + (*sub_len)--; + } + frag_size = MIN(key_size - bits_read, 8 - rpad); + key |= ((uint16_t) ((*byte) >> rpad)) << bits_read; + } + /* Clear extra bits to the left. */ + key &= (1 << key_size) - 1; + *shift = (*shift + key_size) % 8; + return key; +} + +#if LV_GIF_CACHE_DECODE_DATA +/* Decompress image pixels. + * Return 0 on success or -1 on out-of-memory (w.r.t. LZW code table) or parse error. */ +static int +read_image_data(gd_GIF *gif, int interlace) +{ + uint8_t sub_len, shift, byte; + int ret = 0; + int key_size; + int y, pass, linesize; + uint8_t *ptr = NULL; + uint8_t *ptr_row_start = NULL; + uint8_t *ptr_base = NULL; + size_t start, end; + uint16_t key, clear_code, stop_code, curr_code; + int frm_off, frm_size,curr_size,top_slot,new_codes,slot; + /* The first value of the value sequence corresponding to key */ + int first_value; + int last_key; + uint8_t *sp = NULL; + uint8_t *p_stack = NULL; + uint8_t *p_suffix = NULL; + uint16_t *p_prefix = NULL; + + /* get initial key size and clear code, stop code */ + f_gif_read(gif, &byte, 1); + key_size = (int) byte; + clear_code = 1 << key_size; + stop_code = clear_code + 1; + key = 0; + + start = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + discard_sub_blocks(gif); + end = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + f_gif_seek(gif, start, LV_FS_SEEK_SET); + + linesize = gif->width; + ptr_base = &gif->frame[gif->fy * linesize + gif->fx]; + ptr_row_start = ptr_base; + ptr = ptr_row_start; + sub_len = shift = 0; + /* decoder */ + pass = 0; + y = 0; + p_stack = gif->lzw_cache; + p_suffix = gif->lzw_cache + LZW_TABLE_SIZE; + p_prefix = (uint16_t*)(gif->lzw_cache + LZW_TABLE_SIZE * 2); + frm_off = 0; + frm_size = gif->fw * gif->fh; + curr_size = key_size + 1; + top_slot = 1 << curr_size; + new_codes = clear_code + 2; + slot = new_codes; + first_value = -1; + last_key = -1; + sp = p_stack; + + while (frm_off < frm_size) { + /* copy data to frame buffer */ + while (sp > p_stack) { + if(frm_off >= frm_size){ + ESP_LOGW(TAG, "LZW table token overflows the frame buffer"); + return -1; + } + *ptr++ = *(--sp); + frm_off += 1; + /* read one line */ + if ((ptr - ptr_row_start) == gif->fw) { + if (interlace) { + switch(pass) { + case 0: + case 1: + y += 8; + ptr_row_start += linesize * 8; + break; + case 2: + y += 4; + ptr_row_start += linesize * 4; + break; + case 3: + y += 2; + ptr_row_start += linesize * 2; + break; + default: + break; + } + while (y >= gif->fh) { + y = 4 >> pass; + ptr_row_start = ptr_base + linesize * y; + pass++; + } + } else { + ptr_row_start += linesize; + } + ptr = ptr_row_start; + } + } + + key = get_key(gif, curr_size, &sub_len, &shift, &byte); + + if (key == stop_code || key >= LZW_TABLE_SIZE) + break; + + if (key == clear_code) { + curr_size = key_size + 1; + slot = new_codes; + top_slot = 1 << curr_size; + first_value = last_key = -1; + sp = p_stack; + continue; + } + + curr_code = key; + /* + * If the current code is a code that will be added to the decoding + * dictionary, it is composed of the data list corresponding to the + * previous key and its first data. + * */ + if (curr_code == slot && first_value >= 0) { + *sp++ = first_value; + curr_code = last_key; + }else if(curr_code >= slot) + break; + + while (curr_code >= new_codes) { + *sp++ = p_suffix[curr_code]; + curr_code = p_prefix[curr_code]; + } + *sp++ = curr_code; + + /* Add code to decoding dictionary */ + if (slot < top_slot && last_key >= 0) { + p_suffix[slot] = curr_code; + p_prefix[slot++] = last_key; + } + first_value = curr_code; + last_key = key; + if (slot >= top_slot) { + if (curr_size < LZW_MAXBITS) { + top_slot <<= 1; + curr_size += 1; + } + } + } + + if (key == stop_code) f_gif_read(gif, &sub_len, 1); /* Must be zero! */ + f_gif_seek(gif, end, LV_FS_SEEK_SET); + return ret; +} +#else +static Table * +new_table(int key_size) +{ + int key; + int init_bulk = MAX(1 << (key_size + 1), 0x100); + Table * table = lv_malloc(sizeof(*table) + sizeof(Entry) * init_bulk); + if(table) { + table->bulk = init_bulk; + table->nentries = (1 << key_size) + 2; + table->entries = (Entry *) &table[1]; + for(key = 0; key < (1 << key_size); key++) + table->entries[key] = (Entry) { + 1, 0xFFF, key + }; + } + return table; +} + +/* Add table entry. Return value: + * 0 on success + * +1 if key size must be incremented after this addition + * -1 if could not realloc table */ +static int +add_entry(Table ** tablep, uint16_t length, uint16_t prefix, uint8_t suffix) +{ + Table * table = *tablep; + if(table->nentries == table->bulk) { + table->bulk *= 2; + table = lv_realloc(table, sizeof(*table) + sizeof(Entry) * table->bulk); + if(!table) return -1; + table->entries = (Entry *) &table[1]; + *tablep = table; + } + table->entries[table->nentries] = (Entry) { + length, prefix, suffix + }; + table->nentries++; + if((table->nentries & (table->nentries - 1)) == 0) + return 1; + return 0; +} + +/* Compute output index of y-th input line, in frame of height h. */ +static int +interlaced_line_index(int h, int y) +{ + int p; /* number of lines in current pass */ + + p = (h - 1) / 8 + 1; + if(y < p) /* pass 1 */ + return y * 8; + y -= p; + p = (h - 5) / 8 + 1; + if(y < p) /* pass 2 */ + return y * 8 + 4; + y -= p; + p = (h - 3) / 4 + 1; + if(y < p) /* pass 3 */ + return y * 4 + 2; + y -= p; + /* pass 4 */ + return y * 2 + 1; +} + +/* Decompress image pixels. + * Return 0 on success or -1 on out-of-memory (w.r.t. LZW code table) or parse error. */ +static int +read_image_data(gd_GIF * gif, int interlace) +{ + uint8_t sub_len, shift, byte; + int init_key_size, key_size, table_is_full = 0; + int frm_off, frm_size, str_len = 0, i, p, x, y; + uint16_t key, clear, stop; + int ret; + Table * table; + Entry entry = {0}; + size_t start, end; + + f_gif_read(gif, &byte, 1); + key_size = (int) byte; + start = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + discard_sub_blocks(gif); + end = f_gif_seek(gif, 0, LV_FS_SEEK_CUR); + f_gif_seek(gif, start, LV_FS_SEEK_SET); + clear = 1 << key_size; + stop = clear + 1; + table = new_table(key_size); + key_size++; + init_key_size = key_size; + sub_len = shift = 0; + key = get_key(gif, key_size, &sub_len, &shift, &byte); /* clear code */ + frm_off = 0; + ret = 0; + frm_size = gif->fw * gif->fh; + while(frm_off < frm_size) { + if(key == clear) { + key_size = init_key_size; + table->nentries = (1 << (key_size - 1)) + 2; + table_is_full = 0; + } + else if(!table_is_full) { + ret = add_entry(&table, str_len + 1, key, entry.suffix); + if(ret == -1) { + lv_free(table); + return -1; + } + if(table->nentries == 0x1000) { + ret = 0; + table_is_full = 1; + } + } + key = get_key(gif, key_size, &sub_len, &shift, &byte); + if(key == clear) continue; + if(key == stop || key == 0x1000) break; + if(ret == 1) key_size++; + entry = table->entries[key]; + str_len = entry.length; + if(frm_off + str_len > frm_size){ + ESP_LOGW(TAG, "LZW table token overflows the frame buffer"); + lv_free(table); + return -1; + } + for(i = 0; i < str_len; i++) { + p = frm_off + entry.length - 1; + x = p % gif->fw; + y = p / gif->fw; + if(interlace) + y = interlaced_line_index((int) gif->fh, y); + gif->frame[(gif->fy + y) * gif->width + gif->fx + x] = entry.suffix; + if(entry.prefix == 0xFFF) + break; + else + entry = table->entries[entry.prefix]; + } + frm_off += str_len; + if(key < table->nentries - 1 && !table_is_full) + table->entries[table->nentries - 1].suffix = entry.suffix; + } + lv_free(table); + if(key == stop) f_gif_read(gif, &sub_len, 1); /* Must be zero! */ + f_gif_seek(gif, end, LV_FS_SEEK_SET); + return 0; +} + +#endif + +/* Read image. + * Return 0 on success or -1 on out-of-memory (w.r.t. LZW code table) or parse error. */ +static int +read_image(gd_GIF * gif) +{ + uint8_t fisrz; + int interlace; + + /* Image Descriptor. */ + gif->fx = read_num(gif); + gif->fy = read_num(gif); + gif->fw = read_num(gif); + gif->fh = read_num(gif); + if(gif->fx + (uint32_t)gif->fw > gif->width || gif->fy + (uint32_t)gif->fh > gif->height){ + ESP_LOGW(TAG, "Frame coordinates out of image bounds"); + return -1; + } + f_gif_read(gif, &fisrz, 1); + interlace = fisrz & 0x40; + /* Ignore Sort Flag. */ + /* Local Color Table? */ + if(fisrz & 0x80) { + /* Read LCT */ + gif->lct.size = 1 << ((fisrz & 0x07) + 1); + f_gif_read(gif, gif->lct.colors, 3 * gif->lct.size); + gif->palette = &gif->lct; + } + else + gif->palette = &gif->gct; + /* Image Data. */ + return read_image_data(gif, interlace); +} + +static void +render_frame_rect(gd_GIF * gif, uint8_t * buffer) +{ + int i = gif->fy * gif->width + gif->fx; +#ifdef GIFDEC_RENDER_FRAME + GIFDEC_RENDER_FRAME(&buffer[i * 4], gif->fw, gif->fh, gif->width, + &gif->frame[i], gif->palette->colors, + gif->gce.transparency ? gif->gce.tindex : 0x100); +#else + int j, k; + uint8_t index, * color; + + for(j = 0; j < gif->fh; j++) { + for(k = 0; k < gif->fw; k++) { + index = gif->frame[(gif->fy + j) * gif->width + gif->fx + k]; + color = &gif->palette->colors[index * 3]; + if(!gif->gce.transparency || index != gif->gce.tindex) { + buffer[(i + k) * 4 + 0] = *(color + 2); + buffer[(i + k) * 4 + 1] = *(color + 1); + buffer[(i + k) * 4 + 2] = *(color + 0); + buffer[(i + k) * 4 + 3] = 0xFF; + } + } + i += gif->width; + } +#endif +} + +static void +dispose(gd_GIF * gif) +{ + int i; + uint8_t * bgcolor; + switch(gif->gce.disposal) { + case 2: /* Restore to background color. */ + bgcolor = &gif->palette->colors[gif->bgindex * 3]; + + uint8_t opa = 0xff; + if(gif->gce.transparency) opa = 0x00; + + i = gif->fy * gif->width + gif->fx; +#ifdef GIFDEC_FILL_BG + GIFDEC_FILL_BG(&(gif->canvas[i * 4]), gif->fw, gif->fh, gif->width, bgcolor, opa); +#else + int j, k; + for(j = 0; j < gif->fh; j++) { + for(k = 0; k < gif->fw; k++) { + gif->canvas[(i + k) * 4 + 0] = *(bgcolor + 2); + gif->canvas[(i + k) * 4 + 1] = *(bgcolor + 1); + gif->canvas[(i + k) * 4 + 2] = *(bgcolor + 0); + gif->canvas[(i + k) * 4 + 3] = opa; + } + i += gif->width; + } +#endif + break; + case 3: /* Restore to previous, i.e., don't update canvas.*/ + break; + default: + /* Add frame non-transparent pixels to canvas. */ + render_frame_rect(gif, gif->canvas); + } +} + +/* Return 1 if got a frame; 0 if got GIF trailer; -1 if error. */ +int +gd_get_frame(gd_GIF * gif) +{ + char sep; + + dispose(gif); + f_gif_read(gif, &sep, 1); + while(sep != ',') { + if(sep == ';') { + f_gif_seek(gif, gif->anim_start, LV_FS_SEEK_SET); + if(gif->loop_count == 1 || gif->loop_count < 0) { + return 0; + } + else if(gif->loop_count > 1) { + gif->loop_count--; + } + } + else if(sep == '!') + read_ext(gif); + else return -1; + f_gif_read(gif, &sep, 1); + } + if(read_image(gif) == -1) + return -1; + return 1; +} + +void +gd_render_frame(gd_GIF * gif, uint8_t * buffer) +{ + render_frame_rect(gif, buffer); +} + +void +gd_rewind(gd_GIF * gif) +{ + gif->loop_count = -1; + f_gif_seek(gif, gif->anim_start, LV_FS_SEEK_SET); +} + +void +gd_close_gif(gd_GIF * gif) +{ + f_gif_close(gif); + lv_free(gif); +} + +static bool f_gif_open(gd_GIF * gif, const void * path, bool is_file) +{ + gif->f_rw_p = 0; + gif->data = NULL; + gif->is_file = is_file; + + if(is_file) { + lv_fs_res_t res = lv_fs_open(&gif->fd, path, LV_FS_MODE_RD); + if(res != LV_FS_RES_OK) return false; + else return true; + } + else { + gif->data = path; + return true; + } +} + +static void f_gif_read(gd_GIF * gif, void * buf, size_t len) +{ + if(gif->is_file) { + lv_fs_read(&gif->fd, buf, len, NULL); + } + else { + memcpy(buf, &gif->data[gif->f_rw_p], len); + gif->f_rw_p += len; + } +} + +static int f_gif_seek(gd_GIF * gif, size_t pos, int k) +{ + if(gif->is_file) { + lv_fs_seek(&gif->fd, pos, k); + uint32_t x; + lv_fs_tell(&gif->fd, &x); + return x; + } + else { + if(k == LV_FS_SEEK_CUR) gif->f_rw_p += pos; + else if(k == LV_FS_SEEK_SET) gif->f_rw_p = pos; + return gif->f_rw_p; + } +} + +static void f_gif_close(gd_GIF * gif) +{ + if(gif->is_file) { + lv_fs_close(&gif->fd); + } +} + diff --git a/main/display/lvgl_display/gif/gifdec.h b/main/display/lvgl_display/gif/gifdec.h new file mode 100644 index 0000000..12c171e --- /dev/null +++ b/main/display/lvgl_display/gif/gifdec.h @@ -0,0 +1,68 @@ +#ifndef GIFDEC_H +#define GIFDEC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include + +typedef struct _gd_Palette { + int size; + uint8_t colors[0x100 * 3]; +} gd_Palette; + +typedef struct _gd_GCE { + uint16_t delay; + uint8_t tindex; + uint8_t disposal; + int input; + int transparency; +} gd_GCE; + + + +typedef struct _gd_GIF { + lv_fs_file_t fd; + const char * data; + uint8_t is_file; + uint32_t f_rw_p; + int32_t anim_start; + uint16_t width, height; + uint16_t depth; + int32_t loop_count; + gd_GCE gce; + gd_Palette * palette; + gd_Palette lct, gct; + void (*plain_text)( + struct _gd_GIF * gif, uint16_t tx, uint16_t ty, + uint16_t tw, uint16_t th, uint8_t cw, uint8_t ch, + uint8_t fg, uint8_t bg + ); + void (*comment)(struct _gd_GIF * gif); + void (*application)(struct _gd_GIF * gif, char id[8], char auth[3]); + uint16_t fx, fy, fw, fh; + uint8_t bgindex; + uint8_t * canvas, * frame; +#if LV_GIF_CACHE_DECODE_DATA + uint8_t *lzw_cache; +#endif +} gd_GIF; + +gd_GIF * gd_open_gif_file(const char * fname); + +gd_GIF * gd_open_gif_data(const void * data); + +void gd_render_frame(gd_GIF * gif, uint8_t * buffer); + +int gd_get_frame(gd_GIF * gif); +void gd_rewind(gd_GIF * gif); +void gd_close_gif(gd_GIF * gif); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* GIFDEC_H */ diff --git a/main/display/lvgl_display/gif/gifdec_mve.h b/main/display/lvgl_display/gif/gifdec_mve.h new file mode 100644 index 0000000..6d83393 --- /dev/null +++ b/main/display/lvgl_display/gif/gifdec_mve.h @@ -0,0 +1,140 @@ +/** + * @file gifdec_mve.h + * + */ + +#ifndef GIFDEC_MVE_H +#define GIFDEC_MVE_H + +#ifdef __cplusplus +extern "C" { +#endif + +/********************* + * INCLUDES + *********************/ +#include +#include "../../misc/lv_color.h" + +/********************* + * DEFINES + *********************/ + +#define GIFDEC_FILL_BG(dst, w, h, stride, color, opa) \ + _gifdec_fill_bg_mve(dst, w, h, stride, color, opa) + +#define GIFDEC_RENDER_FRAME(dst, w, h, stride, frame, pattern, tindex) \ + _gifdec_render_frame_mve(dst, w, h, stride, frame, pattern, tindex) + +/********************** + * MACROS + **********************/ + +/********************** + * TYPEDEFS + **********************/ + +/********************** + * GLOBAL PROTOTYPES + **********************/ + +static inline void _gifdec_fill_bg_mve(uint8_t * dst, uint16_t w, uint16_t h, uint16_t stride, uint8_t * color, + uint8_t opa) +{ + lv_color32_t c = lv_color32_make(*(color + 0), *(color + 1), *(color + 2), opa); + uint32_t color_32 = *(uint32_t *)&c; + + __asm volatile( + ".p2align 2 \n" + "vdup.32 q0, %[src] \n" + "3: \n" + "mov r0, %[dst] \n" + + "wlstp.32 lr, %[w], 1f \n" + "2: \n" + + "vstrw.32 q0, [r0], #16 \n" + "letp lr, 2b \n" + "1: \n" + "add %[dst], %[iTargetStride] \n" + "subs %[h], #1 \n" + "bne 3b \n" + : [dst] "+r"(dst), + [h] "+r"(h) + : [src] "r"(color_32), + [w] "r"(w), + [iTargetStride] "r"(stride * sizeof(uint32_t)) + : "r0", "q0", "memory", "r14", "cc"); +} + +static inline void _gifdec_render_frame_mve(uint8_t * dst, uint16_t w, uint16_t h, uint16_t stride, uint8_t * frame, + uint8_t * pattern, uint16_t tindex) +{ + if(w == 0 || h == 0) { + return; + } + + __asm volatile( + "vmov.u16 q3, #255 \n" + "vshl.u16 q3, q3, #8 \n" /* left shift 8 for a*/ + + "mov r0, #2 \n" + "vidup.u16 q6, r0, #4 \n" /* [2, 6, 10, 14, 18, 22, 26, 30] */ + "mov r0, #0 \n" + "vidup.u16 q7, r0, #4 \n" /* [0, 4, 8, 12, 16, 20, 24, 28] */ + + "3: \n" + "mov r1, %[dst] \n" + "mov r2, %[frame] \n" + + "wlstp.16 lr, %[w], 1f \n" + "2: \n" + + "mov r0, #3 \n" + "vldrb.u16 q4, [r2], #8 \n" + "vmul.u16 q5, q4, r0 \n" + + "mov r0, #1 \n" + "vldrb.u16 q2, [%[pattern], q5] \n" /* load 8 pixel r*/ + + "vadd.u16 q5, q5, r0 \n" + "vldrb.u16 q1, [%[pattern], q5] \n" /* load 8 pixel g*/ + + "vadd.u16 q5, q5, r0 \n" + "vldrb.u16 q0, [%[pattern], q5] \n" /* load 8 pixel b*/ + + "vshl.u16 q1, q1, #8 \n" /* left shift 8 for g*/ + + "vorr.u16 q0, q0, q1 \n" /* make 8 pixel gb*/ + "vorr.u16 q1, q2, q3 \n" /* make 8 pixel ar*/ + + "vcmp.i16 ne, q4, %[tindex] \n" + "vpstt \n" + "vstrht.16 q0, [r1, q7] \n" + "vstrht.16 q1, [r1, q6] \n" + "add r1, r1, #32 \n" + + "letp lr, 2b \n" + + "1: \n" + "mov r0, %[stride], LSL #2 \n" + "add %[dst], r0 \n" + "add %[frame], %[stride] \n" + "subs %[h], #1 \n" + "bne 3b \n" + + : [dst] "+r"(dst), + [frame] "+r"(frame), + [h] "+r"(h) + : [pattern] "r"(pattern), + [w] "r"(w), + [stride] "r"(stride), + [tindex] "r"(tindex) + : "r0", "r1", "r2", "q0", "q1", "q2", "q3", "q4", "q5", "q6", "q7", "memory", "r14", "cc"); +} + +#ifdef __cplusplus +} /*extern "C"*/ +#endif + +#endif /*GIFDEC_MVE_H*/ diff --git a/main/display/lvgl_display/gif/lvgl_gif.cc b/main/display/lvgl_display/gif/lvgl_gif.cc new file mode 100644 index 0000000..172d5ba --- /dev/null +++ b/main/display/lvgl_display/gif/lvgl_gif.cc @@ -0,0 +1,208 @@ +#include "lvgl_gif.h" +#include +#include + +#define TAG "LvglGif" + +LvglGif::LvglGif(const lv_img_dsc_t* img_dsc) + : gif_(nullptr), timer_(nullptr), last_call_(0), playing_(false), loaded_(false) { + if (!img_dsc || !img_dsc->data) { + ESP_LOGE(TAG, "Invalid image descriptor"); + return; + } + + gif_ = gd_open_gif_data(img_dsc->data); + if (!gif_) { + ESP_LOGE(TAG, "Failed to open GIF from image descriptor"); + return; + } + + // Setup LVGL image descriptor + memset(&img_dsc_, 0, sizeof(img_dsc_)); + img_dsc_.header.magic = LV_IMAGE_HEADER_MAGIC; + img_dsc_.header.flags = LV_IMAGE_FLAGS_MODIFIABLE; + img_dsc_.header.cf = LV_COLOR_FORMAT_ARGB8888; + img_dsc_.header.w = gif_->width; + img_dsc_.header.h = gif_->height; + img_dsc_.header.stride = gif_->width * 4; + img_dsc_.data = gif_->canvas; + img_dsc_.data_size = gif_->width * gif_->height * 4; + + // Render first frame + if (gif_->canvas) { + gd_render_frame(gif_, gif_->canvas); + } + + loaded_ = true; + ESP_LOGD(TAG, "GIF loaded from image descriptor: %dx%d", gif_->width, gif_->height); +} + +// Destructor +LvglGif::~LvglGif() { + Cleanup(); +} + +// LvglImage interface implementation +const lv_img_dsc_t* LvglGif::image_dsc() const { + if (!loaded_) { + return nullptr; + } + return &img_dsc_; +} + +// Animation control methods +void LvglGif::Start() { + if (!loaded_ || !gif_) { + ESP_LOGW(TAG, "GIF not loaded, cannot start"); + return; + } + + if (!timer_) { + timer_ = lv_timer_create([](lv_timer_t* timer) { + LvglGif* gif_obj = static_cast(lv_timer_get_user_data(timer)); + gif_obj->NextFrame(); + }, 10, this); + } + + if (timer_) { + playing_ = true; + last_call_ = lv_tick_get(); + lv_timer_resume(timer_); + lv_timer_reset(timer_); + + // Render first frame + NextFrame(); + + ESP_LOGD(TAG, "GIF animation started"); + } +} + +void LvglGif::Pause() { + if (timer_) { + playing_ = false; + lv_timer_pause(timer_); + ESP_LOGD(TAG, "GIF animation paused"); + } +} + +void LvglGif::Resume() { + if (!loaded_ || !gif_) { + ESP_LOGW(TAG, "GIF not loaded, cannot resume"); + return; + } + + if (timer_) { + playing_ = true; + lv_timer_resume(timer_); + ESP_LOGD(TAG, "GIF animation resumed"); + } +} + +void LvglGif::Stop() { + if (timer_) { + playing_ = false; + lv_timer_pause(timer_); + } + + if (gif_) { + gd_rewind(gif_); + NextFrame(); + ESP_LOGD(TAG, "GIF animation stopped and rewound"); + } +} + +bool LvglGif::IsPlaying() const { + return playing_; +} + +bool LvglGif::IsLoaded() const { + return loaded_; +} + +int32_t LvglGif::GetLoopCount() const { + if (!loaded_ || !gif_) { + return -1; + } + return gif_->loop_count; +} + +void LvglGif::SetLoopCount(int32_t count) { + if (!loaded_ || !gif_) { + ESP_LOGW(TAG, "GIF not loaded, cannot set loop count"); + return; + } + gif_->loop_count = count; +} + +uint16_t LvglGif::width() const { + if (!loaded_ || !gif_) { + return 0; + } + return gif_->width; +} + +uint16_t LvglGif::height() const { + if (!loaded_ || !gif_) { + return 0; + } + return gif_->height; +} + +void LvglGif::SetFrameCallback(std::function callback) { + frame_callback_ = callback; +} + +void LvglGif::NextFrame() { + if (!loaded_ || !gif_ || !playing_) { + return; + } + + // Check if enough time has passed for the next frame + uint32_t elapsed = lv_tick_elaps(last_call_); + if (elapsed < gif_->gce.delay * 10) { + return; + } + + last_call_ = lv_tick_get(); + + // Get next frame + int has_next = gd_get_frame(gif_); + if (has_next == 0) { + // Animation finished, pause timer + playing_ = false; + if (timer_) { + lv_timer_pause(timer_); + } + ESP_LOGD(TAG, "GIF animation completed"); + } + + // Render current frame + if (gif_->canvas) { + gd_render_frame(gif_, gif_->canvas); + + // Call frame callback if set + if (frame_callback_) { + frame_callback_(); + } + } +} + +void LvglGif::Cleanup() { + // Stop and delete timer + if (timer_) { + lv_timer_delete(timer_); + timer_ = nullptr; + } + + // Close GIF decoder + if (gif_) { + gd_close_gif(gif_); + gif_ = nullptr; + } + + playing_ = false; + loaded_ = false; + + // Clear image descriptor + memset(&img_dsc_, 0, sizeof(img_dsc_)); +} diff --git a/main/display/lvgl_display/gif/lvgl_gif.h b/main/display/lvgl_display/gif/lvgl_gif.h new file mode 100644 index 0000000..afa2959 --- /dev/null +++ b/main/display/lvgl_display/gif/lvgl_gif.h @@ -0,0 +1,101 @@ +#pragma once + +#include "../lvgl_image.h" +#include "gifdec.h" +#include +#include +#include + +/** + * C++ implementation of LVGL GIF widget + * Provides GIF animation functionality using gifdec library + */ +class LvglGif { +public: + explicit LvglGif(const lv_img_dsc_t* img_dsc); + virtual ~LvglGif(); + + // LvglImage interface implementation + virtual const lv_img_dsc_t* image_dsc() const; + + /** + * Start/restart GIF animation + */ + void Start(); + + /** + * Pause GIF animation + */ + void Pause(); + + /** + * Resume GIF animation + */ + void Resume(); + + /** + * Stop GIF animation and rewind to first frame + */ + void Stop(); + + /** + * Check if GIF is currently playing + */ + bool IsPlaying() const; + + /** + * Check if GIF was loaded successfully + */ + bool IsLoaded() const; + + /** + * Get loop count + */ + int32_t GetLoopCount() const; + + /** + * Set loop count + */ + void SetLoopCount(int32_t count); + + /** + * Get GIF dimensions + */ + uint16_t width() const; + uint16_t height() const; + + /** + * Set frame update callback + */ + void SetFrameCallback(std::function callback); + +private: + // GIF decoder instance + gd_GIF* gif_; + + // LVGL image descriptor + lv_img_dsc_t img_dsc_; + + // Animation timer + lv_timer_t* timer_; + + // Last frame update time + uint32_t last_call_; + + // Animation state + bool playing_; + bool loaded_; + + // Frame update callback + std::function frame_callback_; + + /** + * Update to next frame + */ + void NextFrame(); + + /** + * Cleanup resources + */ + void Cleanup(); +}; diff --git a/main/display/lvgl_display/jpg/image_to_jpeg.cpp b/main/display/lvgl_display/jpg/image_to_jpeg.cpp new file mode 100644 index 0000000..485ca8b --- /dev/null +++ b/main/display/lvgl_display/jpg/image_to_jpeg.cpp @@ -0,0 +1,467 @@ +#include +#include +#include +#include +#include +#include + +#include "esp_jpeg_common.h" +#include "esp_jpeg_enc.h" +#include "esp_imgfx_color_convert.h" + +#if CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER +#include "driver/jpeg_encode.h" +#endif +#include "image_to_jpeg.h" + +#define TAG "image_to_jpeg" + +static void* malloc_psram(size_t size) { + void* p = malloc(size); + if (p) + return p; +#if (CONFIG_SPIRAM_SUPPORT && (CONFIG_SPIRAM_USE_CAPS_ALLOC || CONFIG_SPIRAM_USE_MALLOC)) + return heap_caps_malloc(size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); +#else + return NULL; +#endif +} + +static __always_inline uint8_t expand_5_to_8(uint8_t v) { + return (uint8_t)((v << 3) | (v >> 2)); +} + +static __always_inline uint8_t expand_6_to_8(uint8_t v) { + return (uint8_t)((v << 2) | (v >> 4)); +} + +static uint8_t* convert_input_to_encoder_buf(const uint8_t* src, uint16_t width, uint16_t height, v4l2_pix_fmt_t format, + jpeg_pixel_format_t* out_fmt, int* out_size) { + // GRAY 直接作为 JPEG_PIXEL_FORMAT_GRAY 输入 + if (format == V4L2_PIX_FMT_GREY) { + int sz = (int)width * (int)height; + uint8_t* buf = (uint8_t*)jpeg_calloc_align(sz, 16); + if (!buf) + return NULL; + memcpy(buf, src, sz); + if (out_fmt) + *out_fmt = JPEG_PIXEL_FORMAT_GRAY; + if (out_size) + *out_size = sz; + return buf; + } + + // V4L2 YUYV (Y Cb Y Cr) 可直接作为 JPEG_PIXEL_FORMAT_YCbYCr 输入 + if (format == V4L2_PIX_FMT_YUYV) { + int sz = (int)width * (int)height * 2; + uint8_t* buf = (uint8_t*)jpeg_calloc_align(sz, 16); + if (!buf) + return NULL; + memcpy(buf, src, sz); + if (out_fmt) + *out_fmt = JPEG_PIXEL_FORMAT_YCbYCr; + if (out_size) + *out_size = sz; + return buf; + } + + // V4L2 UYVY (Cb Y Cr Y) -> 重排为 YUYV 再作为 YCbYCr 输入 + // 当前版本暂时不会出现 UYVY 格式 + if (format == V4L2_PIX_FMT_UYVY) [[unlikely]] { + int sz = (int)width * (int)height * 2; + const uint8_t* s = src; + uint8_t* buf = (uint8_t*)jpeg_calloc_align(sz, 16); + if (!buf) + return NULL; + uint8_t* d = buf; + for (int i = 0; i < sz; i += 4) { + // src: Cb, Y0, Cr, Y1 -> dst: Y0, Cb, Y1, Cr + d[0] = s[1]; + d[1] = s[0]; + d[2] = s[3]; + d[3] = s[2]; + s += 4; + d += 4; + } + if (out_fmt) + *out_fmt = JPEG_PIXEL_FORMAT_YCbYCr; + if (out_size) + *out_size = sz; + return buf; + } + + // V4L2 YUV422P (YUV422 Planar) -> 重排为 YUYV (YCbYCr) + // 当前版本暂时不会出现 YUV422P 格式 + if (format == V4L2_PIX_FMT_YUV422P) [[unlikely]] { + int sz = (int)width * (int)height * 2; + const uint8_t* y_plane = src; + const uint8_t* u_plane = y_plane + (int)width * (int)height; + const uint8_t* v_plane = u_plane + ((int)width / 2) * (int)height; + uint8_t* buf = (uint8_t*)jpeg_calloc_align(sz, 16); + if (!buf) + return NULL; + uint8_t* dst = buf; + for (int y = 0; y < height; y++) { + const uint8_t* y_row = y_plane + y * (int)width; + const uint8_t* u_row = u_plane + y * ((int)width / 2); + const uint8_t* v_row = v_plane + y * ((int)width / 2); + for (int x = 0; x < width; x += 2) { + uint8_t y0 = y_row[x + 0]; + uint8_t y1 = y_row[x + 1]; + uint8_t cb = u_row[x / 2]; + uint8_t cr = v_row[x / 2]; + dst[0] = y0; + dst[1] = cb; + dst[2] = y1; + dst[3] = cr; + dst += 4; + } + } + if (out_fmt) + *out_fmt = JPEG_PIXEL_FORMAT_YCbYCr; + if (out_size) + *out_size = sz; + return buf; + } + + // RGB 转换为 YUV422 (YCbYCr) 再输入 + // 见 https://github.com/78/xiaozhi-esp32/issues/1380#issuecomment-3497156378 + else if (format == V4L2_PIX_FMT_RGB24 || format == V4L2_PIX_FMT_RGB565 || format == V4L2_PIX_FMT_RGB565X) { + esp_imgfx_pixel_fmt_t in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB888; + uint32_t src_len = 0; + switch (format) { + case V4L2_PIX_FMT_RGB24: + in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB888; + src_len = static_cast(width * height * 3); + break; + case V4L2_PIX_FMT_RGB565: + in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB565_LE; + src_len = static_cast(width * height * 2); + break; + [[unlikely]] case V4L2_PIX_FMT_RGB565X: // 当前版本暂时不会出现 RGB565X + in_pixel_fmt = ESP_IMGFX_PIXEL_FMT_RGB565_BE; + src_len = static_cast(width * height * 2); + break; + [[unlikely]] default: + ESP_LOGE(TAG, "[Unreachable Case] unsupported format: 0x%08lx", format); + std::unreachable(); + } + int sz = (int)width * (int)height * 2; + uint8_t* buf = (uint8_t*)jpeg_calloc_align(sz, 16); + if (!buf) + return nullptr; + esp_imgfx_color_convert_cfg_t convert_cfg = { + .in_res = {.width = static_cast(width), + .height = static_cast(height)}, + .in_pixel_fmt = in_pixel_fmt, + .out_pixel_fmt = ESP_IMGFX_PIXEL_FMT_YUYV, + .color_space_std = ESP_IMGFX_COLOR_SPACE_STD_BT601, + }; + esp_imgfx_color_convert_handle_t convert_handle = nullptr; + esp_imgfx_err_t err = esp_imgfx_color_convert_open(&convert_cfg, &convert_handle); + if (err != ESP_IMGFX_ERR_OK || convert_handle == nullptr) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_open failed"); + jpeg_free_align(buf); + return nullptr; + } + esp_imgfx_data_t convert_input_data = { + .data = const_cast(src), + .data_len = static_cast(src_len), + }; + esp_imgfx_data_t convert_output_data = { + .data = buf, + .data_len = static_cast(sz), + }; + err = esp_imgfx_color_convert_process(convert_handle, &convert_input_data, &convert_output_data); + if (err != ESP_IMGFX_ERR_OK) { + ESP_LOGE(TAG, "esp_imgfx_color_convert_process failed"); + jpeg_free_align(buf); + return nullptr; + } + esp_imgfx_color_convert_close(convert_handle); + convert_handle = nullptr; + if (out_fmt) + *out_fmt = JPEG_PIXEL_FORMAT_YCbYCr; + if (out_size) + *out_size = sz; + return buf; + } + ESP_LOGE(TAG, "unsupported format: 0x%08lx", format); + if (out_size) + *out_size = 0; + return nullptr; +} + +#if CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER +static jpeg_encoder_handle_t s_hw_jpeg_handle = NULL; + +static bool hw_jpeg_ensure_inited(void) { + if (s_hw_jpeg_handle) { + return true; + } + jpeg_encode_engine_cfg_t eng_cfg = { + .intr_priority = 0, + .timeout_ms = 100, + }; + esp_err_t er = jpeg_new_encoder_engine(&eng_cfg, &s_hw_jpeg_handle); + if (er != ESP_OK) { + ESP_LOGE(TAG, "jpeg_new_encoder_engine failed: %d", (int)er); + s_hw_jpeg_handle = NULL; + return false; + } + return true; +} + +static uint8_t* convert_input_to_hw_encoder_buf(const uint8_t* src, uint16_t width, uint16_t height, v4l2_pix_fmt_t format, + jpeg_enc_input_format_t* out_fmt, int* out_size) { + if (format == V4L2_PIX_FMT_GREY) { + int sz = (int)width * (int)height; + uint8_t* buf = (uint8_t*)malloc_psram(sz); + if (!buf) + return NULL; + memcpy(buf, src, sz); + if (out_fmt) + *out_fmt = JPEG_ENCODE_IN_FORMAT_GRAY; + if (out_size) + *out_size = sz; + return buf; + } + + if (format == V4L2_PIX_FMT_RGB24) { + int sz = (int)width * (int)height * 3; + uint8_t* buf = (uint8_t*)malloc_psram(sz); + if (!buf) { + ESP_LOGE(TAG, "malloc_psram failed"); + return NULL; + } + memcpy(buf, src, sz); + if (out_fmt) + *out_fmt = JPEG_ENCODE_IN_FORMAT_RGB888; + if (out_size) + *out_size = sz; + return buf; + } + + if (format == V4L2_PIX_FMT_RGB565) { + int sz = (int)width * (int)height * 2; + uint8_t* buf = (uint8_t*)malloc_psram(sz); + if (!buf) + return NULL; + memcpy(buf, src, sz); + if (out_fmt) + *out_fmt = JPEG_ENCODE_IN_FORMAT_RGB565; + if (out_size) + *out_size = sz; + return buf; + } + + if (format == V4L2_PIX_FMT_YUYV) { + // 硬件需要 | Y1 V Y0 U | 的“大端”格式,因此需要 bswap16 + int sz = (int)width * (int)height * 2; + uint16_t* buf = (uint16_t*)malloc_psram(sz); + if (!buf) + return NULL; + const uint16_t* bsrc = (const uint16_t*)src; + for (int i = 0; i < sz / 2; i++) { + buf[i] = __builtin_bswap16(bsrc[i]); + } + if (out_fmt) + *out_fmt = JPEG_ENCODE_IN_FORMAT_YUV422; + if (out_size) + *out_size = sz; + return (uint8_t*)buf; + } + + return NULL; +} + +static bool encode_with_hw_jpeg(const uint8_t* src, size_t src_len, uint16_t width, uint16_t height, + v4l2_pix_fmt_t format, uint8_t quality, uint8_t** jpg_out, size_t* jpg_out_len, + jpg_out_cb cb, void* cb_arg) { + if (quality < 1) + quality = 1; + if (quality > 100) + quality = 100; + + jpeg_enc_input_format_t enc_src_type = JPEG_ENCODE_IN_FORMAT_RGB888; + int enc_in_size = 0; + uint8_t* enc_in = convert_input_to_hw_encoder_buf(src, width, height, format, &enc_src_type, &enc_in_size); + if (!enc_in) { + ESP_LOGW(TAG, "hw jpeg: unsupported format, fallback to sw"); + return false; + } + + if (!hw_jpeg_ensure_inited()) { + free(enc_in); + return false; + } + + jpeg_encode_cfg_t enc_cfg = {0}; + enc_cfg.width = width; + enc_cfg.height = height; + enc_cfg.src_type = enc_src_type; + enc_cfg.image_quality = quality; + enc_cfg.sub_sample = (enc_src_type == JPEG_ENCODE_IN_FORMAT_GRAY) ? JPEG_DOWN_SAMPLING_GRAY : JPEG_DOWN_SAMPLING_YUV422; + + size_t out_cap = (size_t)width * (size_t)height * 3 / 2 + 64 * 1024; + if (out_cap < 128 * 1024) + out_cap = 128 * 1024; + jpeg_encode_memory_alloc_cfg_t jpeg_enc_output_mem_cfg = { .buffer_direction = JPEG_ENC_ALLOC_OUTPUT_BUFFER }; + size_t out_cap_aligned = 0; + uint8_t* outbuf = (uint8_t*)jpeg_alloc_encoder_mem(out_cap, &jpeg_enc_output_mem_cfg, &out_cap_aligned); + if (!outbuf) { + free(enc_in); + ESP_LOGE(TAG, "alloc out buffer failed"); + return false; + } + + uint32_t out_len = 0; + esp_err_t er = jpeg_encoder_process(s_hw_jpeg_handle, &enc_cfg, enc_in, (uint32_t)enc_in_size, outbuf, (uint32_t)out_cap_aligned, &out_len); + free(enc_in); + + if (er != ESP_OK) { + free(outbuf); + ESP_LOGE(TAG, "jpeg_encoder_process failed: %d", (int)er); + return false; + } + + if (cb) { + cb(cb_arg, 0, outbuf, (size_t)out_len); + cb(cb_arg, 1, NULL, 0); + free(outbuf); + if (jpg_out) + *jpg_out = NULL; + if (jpg_out_len) + *jpg_out_len = 0; + return true; + } + + if (jpg_out && jpg_out_len) { + *jpg_out = outbuf; + *jpg_out_len = (size_t)out_len; + return true; + } + + free(outbuf); + return true; +} +#endif // CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + +static bool encode_with_esp_new_jpeg(const uint8_t* src, size_t src_len, uint16_t width, uint16_t height, + v4l2_pix_fmt_t format, uint8_t quality, uint8_t** jpg_out, size_t* jpg_out_len, + jpg_out_cb cb, void* cb_arg) { + if (quality < 1) + quality = 1; + if (quality > 100) + quality = 100; + + jpeg_pixel_format_t enc_src_type = JPEG_PIXEL_FORMAT_RGB888; + int enc_in_size = 0; + uint8_t* enc_in = convert_input_to_encoder_buf(src, width, height, format, &enc_src_type, &enc_in_size); + if (!enc_in) { + ESP_LOGE(TAG, "alloc/convert input failed"); + return false; + } + + jpeg_enc_config_t cfg = DEFAULT_JPEG_ENC_CONFIG(); + cfg.width = width; + cfg.height = height; + cfg.src_type = enc_src_type; + cfg.subsampling = (enc_src_type == JPEG_PIXEL_FORMAT_GRAY) ? JPEG_SUBSAMPLE_GRAY : JPEG_SUBSAMPLE_420; + cfg.quality = quality; + cfg.rotate = JPEG_ROTATE_0D; + cfg.task_enable = false; + + jpeg_enc_handle_t h = NULL; + jpeg_error_t ret = jpeg_enc_open(&cfg, &h); + if (ret != JPEG_ERR_OK) { + jpeg_free_align(enc_in); + ESP_LOGE(TAG, "jpeg_enc_open failed: %d", (int)ret); + return false; + } + + // 估算输出缓冲区:宽高的 1.5 倍 + 64KB + size_t out_cap = (size_t)width * (size_t)height * 3 / 2 + 64 * 1024; + if (out_cap < 128 * 1024) + out_cap = 128 * 1024; + uint8_t* outbuf = (uint8_t*)malloc_psram(out_cap); + if (!outbuf) { + jpeg_enc_close(h); + jpeg_free_align(enc_in); + ESP_LOGE(TAG, "alloc out buffer failed"); + return false; + } + + int out_len = 0; + ret = jpeg_enc_process(h, enc_in, enc_in_size, outbuf, (int)out_cap, &out_len); + jpeg_enc_close(h); + jpeg_free_align(enc_in); + + if (ret != JPEG_ERR_OK) { + free(outbuf); + ESP_LOGE(TAG, "jpeg_enc_process failed: %d", (int)ret); + return false; + } + + if (cb) { + cb(cb_arg, 0, outbuf, (size_t)out_len); + cb(cb_arg, 1, NULL, 0); // 结束信号 + free(outbuf); + if (jpg_out) + *jpg_out = NULL; + if (jpg_out_len) + *jpg_out_len = 0; + return true; + } + + if (jpg_out && jpg_out_len) { + *jpg_out = outbuf; + *jpg_out_len = (size_t)out_len; + return true; + } + + free(outbuf); + return true; +} + +bool image_to_jpeg(uint8_t* src, size_t src_len, uint16_t width, uint16_t height, v4l2_pix_fmt_t format, + uint8_t quality, uint8_t** out, size_t* out_len) { +#ifdef CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + if (format == V4L2_PIX_FMT_JPEG) { + uint8_t * out_data = (uint8_t*)heap_caps_malloc(src_len, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT); + if (!out_data) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG output"); + return false; + } + memcpy(out_data, src, src_len); + *out = out_data; + *out_len = src_len; + return true; + } +#endif // CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT +#if CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + if (encode_with_hw_jpeg(src, src_len, width, height, format, quality, out, out_len, NULL, NULL)) { + return true; + } + // Fallback to esp_new_jpeg +#endif + return encode_with_esp_new_jpeg(src, src_len, width, height, format, quality, out, out_len, NULL, NULL); +} + +bool image_to_jpeg_cb(uint8_t* src, size_t src_len, uint16_t width, uint16_t height, v4l2_pix_fmt_t format, + uint8_t quality, jpg_out_cb cb, void* arg) { +#ifdef CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT + if (format == V4L2_PIX_FMT_JPEG) { + cb(arg, 0, src, src_len); + cb(arg, 1, nullptr, 0); // end signal + return true; + } +#endif // CONFIG_XIAOZHI_CAMERA_ALLOW_JPEG_INPUT +#if CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_ENCODER + if (encode_with_hw_jpeg(src, src_len, width, height, format, quality, NULL, NULL, cb, arg)) { + return true; + } + // Fallback to esp_new_jpeg +#endif + return encode_with_esp_new_jpeg(src, src_len, width, height, format, quality, NULL, NULL, cb, arg); +} diff --git a/main/display/lvgl_display/jpg/image_to_jpeg.h b/main/display/lvgl_display/jpg/image_to_jpeg.h new file mode 100644 index 0000000..61898c2 --- /dev/null +++ b/main/display/lvgl_display/jpg/image_to_jpeg.h @@ -0,0 +1,70 @@ +// image_to_jpeg.h - 图像到JPEG转换的高效编码接口 +// 节省约8KB SRAM的JPEG编码实现 +#pragma once +#include "sdkconfig.h" +#ifndef CONFIG_IDF_TARGET_ESP32 + +#include +#include +#include + +typedef uint32_t v4l2_pix_fmt_t; // see linux/videodev2.h for details + +#ifdef __cplusplus +extern "C" { +#endif + +// JPEG输出回调函数类型 +// arg: 用户自定义参数, index: 当前数据索引, data: JPEG数据块, len: 数据块长度 +// 返回: 实际处理的字节数 +typedef size_t (*jpg_out_cb)(void *arg, size_t index, const void *data, size_t len); + +/** + * @brief 将图像格式高效转换为JPEG + * + * 这个函数使用优化的JPEG编码器进行编码,主要特点: + * - 节省约8KB的SRAM使用(静态变量改为堆分配) + * - 支持多种图像格式输入 + * - 高质量JPEG输出 + * + * @param src 源图像数据 + * @param src_len 源图像数据长度 + * @param width 图像宽度 + * @param height 图像高度 + * @param format 图像格式 (PIXFORMAT_RGB565, PIXFORMAT_RGB888, 等) + * @param quality JPEG质量 (1-100) + * @param out 输出JPEG数据指针 (需要调用者释放) + * @param out_len 输出JPEG数据长度 + * + * @return true 成功, false 失败 + */ +bool image_to_jpeg(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, + v4l2_pix_fmt_t format, uint8_t quality, uint8_t **out, size_t *out_len); + +/** + * @brief 将图像格式转换为JPEG(回调版本) + * + * 使用回调函数处理JPEG输出数据,适合流式传输或分块处理: + * - 节省约8KB的SRAM使用(静态变量改为堆分配) + * - 支持流式输出,无需预分配大缓冲区 + * - 通过回调函数逐块处理JPEG数据 + * + * @param src 源图像数据 + * @param src_len 源图像数据长度 + * @param width 图像宽度 + * @param height 图像高度 + * @param format 图像格式 + * @param quality JPEG质量 (1-100) + * @param cb 输出回调函数 + * @param arg 传递给回调函数的用户参数 + * + * @return true 成功, false 失败 + */ +bool image_to_jpeg_cb(uint8_t *src, size_t src_len, uint16_t width, uint16_t height, + v4l2_pix_fmt_t format, uint8_t quality, jpg_out_cb cb, void *arg); + +#ifdef __cplusplus +} +#endif + +#endif // ndef CONFIG_IDF_TARGET_ESP32 diff --git a/main/display/lvgl_display/jpg/jpeg_to_image.c b/main/display/lvgl_display/jpg/jpeg_to_image.c new file mode 100644 index 0000000..da92455 --- /dev/null +++ b/main/display/lvgl_display/jpg/jpeg_to_image.c @@ -0,0 +1,264 @@ +#include +#include +#include +#include + +#include "esp_jpeg_common.h" +#include "esp_jpeg_dec.h" + +#include "jpeg_to_image.h" + +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE +#undef LOG_LOCAL_LEVEL +#define LOG_LOCAL_LEVEL MAX(CONFIG_LOG_DEFAULT_LEVEL, ESP_LOG_DEBUG) +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE +#include + +#ifdef CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER +#include "driver/jpeg_decode.h" +#endif + +#define TAG "jpeg_to_image" + +static esp_err_t decode_with_new_jpeg(const uint8_t* src, size_t src_len, uint8_t** out, size_t* out_len, size_t* width, + size_t* height, size_t* stride) { + ESP_LOGD(TAG, "Decoding JPEG with software decoder"); + esp_err_t ret = ESP_OK; + jpeg_error_t jpeg_ret = JPEG_ERR_OK; + uint8_t* out_buf = NULL; + jpeg_dec_io_t jpeg_io = {0}; + jpeg_dec_header_info_t out_info = {0}; + + jpeg_dec_config_t config = DEFAULT_JPEG_DEC_CONFIG(); + config.output_type = JPEG_PIXEL_FORMAT_RGB565_LE; + config.rotate = JPEG_ROTATE_0D; + + jpeg_dec_handle_t jpeg_dec = NULL; + jpeg_ret = jpeg_dec_open(&config, &jpeg_dec); + if (jpeg_ret != JPEG_ERR_OK) { + ESP_LOGE(TAG, "Failed to open JPEG decoder"); + ret = ESP_FAIL; + goto jpeg_dec_failed; + } + + jpeg_io.inbuf = (uint8_t*)src; + jpeg_io.inbuf_len = (int)src_len; + + jpeg_ret = jpeg_dec_parse_header(jpeg_dec, &jpeg_io, &out_info); + if (jpeg_ret != JPEG_ERR_OK) { + ESP_LOGE(TAG, "Failed to parse JPEG header"); + ret = ESP_ERR_INVALID_ARG; + goto jpeg_dec_failed; + } + + ESP_LOGD(TAG, "JPEG header info: width=%d, height=%d", out_info.width, out_info.height); + + out_buf = jpeg_calloc_align(out_info.width * out_info.height * 2, 16); + if (out_buf == NULL) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG output buffer"); + ret = ESP_ERR_NO_MEM; + goto jpeg_dec_failed; + } + + jpeg_io.outbuf = out_buf; + jpeg_ret = jpeg_dec_process(jpeg_dec, &jpeg_io); + if (jpeg_ret != JPEG_ERR_OK) { + ESP_LOGE(TAG, "Failed to decode JPEG"); + ret = ESP_FAIL; + goto jpeg_dec_failed; + } + + ESP_LOG_BUFFER_HEXDUMP(TAG, out_buf, MIN(out_info.width * out_info.height * 2, 256), ESP_LOG_DEBUG); + + *out = out_buf; + out_buf = NULL; + *out_len = (size_t)(out_info.width * out_info.height * 2); + *width = (size_t)out_info.width; + *height = (size_t)out_info.height; + *stride = (size_t)out_info.width * 2; + jpeg_dec_close(jpeg_dec); + jpeg_dec = NULL; + + return ret; + +jpeg_dec_failed: + if (jpeg_dec) { + jpeg_dec_close(jpeg_dec); + jpeg_dec = NULL; + } + if (out_buf) { + jpeg_free_align(out_buf); + out_buf = NULL; + } + + *out = NULL; + *out_len = 0; + *width = 0; + *height = 0; + *stride = 0; + return ret; +} + +#ifdef CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER +static esp_err_t decode_with_hardware_jpeg(const uint8_t* src, size_t src_len, uint8_t** out, size_t* out_len, + size_t* width, size_t* height, size_t* stride) { + ESP_LOGD(TAG, "Decoding JPEG with hardware decoder"); + esp_err_t ret = ESP_OK; + + jpeg_decoder_handle_t jpeg_dec = NULL; + uint8_t* bit_stream = NULL; + uint8_t* out_buf = NULL; + size_t out_buf_len = 0; + size_t tx_buffer_size = 0; + size_t rx_buffer_size = 0; + + jpeg_decode_engine_cfg_t eng_cfg = { + .intr_priority = 1, + .timeout_ms = 1000, + }; + + jpeg_decode_cfg_t decode_cfg_rgb = { + .output_format = JPEG_DECODE_OUT_FORMAT_RGB565, + .rgb_order = JPEG_DEC_RGB_ELEMENT_ORDER_BGR, + }; + + ret = jpeg_new_decoder_engine(&eng_cfg, &jpeg_dec); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "Failed to create JPEG decoder engine"); + goto jpeg_hw_dec_failed; + } + + jpeg_decode_memory_alloc_cfg_t tx_mem_cfg = { + .buffer_direction = JPEG_DEC_ALLOC_INPUT_BUFFER, + }; + + jpeg_decode_memory_alloc_cfg_t rx_mem_cfg = { + .buffer_direction = JPEG_DEC_ALLOC_OUTPUT_BUFFER, + }; + + bit_stream = (uint8_t*)jpeg_alloc_decoder_mem(src_len, &tx_mem_cfg, &tx_buffer_size); + if (bit_stream == NULL || tx_buffer_size < src_len) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG bit stream"); + ret = ESP_ERR_NO_MEM; + goto jpeg_hw_dec_failed; + } + + memcpy(bit_stream, src, src_len); + + jpeg_decode_picture_info_t header_info; + ESP_GOTO_ON_ERROR(jpeg_decoder_get_info(bit_stream, src_len, &header_info), jpeg_hw_dec_failed, TAG, + "Failed to get JPEG header info"); + + ESP_LOGD(TAG, "JPEG header info: width=%d, height=%d, sample_method=%d", header_info.width, header_info.height, + (int)header_info.sample_method); + + switch (header_info.sample_method) { + case JPEG_DOWN_SAMPLING_GRAY: + case JPEG_DOWN_SAMPLING_YUV444: + out_buf_len = header_info.width * header_info.height * 2; + *stride = header_info.width * 2; + break; + case JPEG_DOWN_SAMPLING_YUV422: + case JPEG_DOWN_SAMPLING_YUV420: + out_buf_len = ((header_info.width + 15) & ~15) * ((header_info.height + 15) & ~15) * 2; + *stride = ((header_info.width + 15) & ~15) * 2; + break; + default: + ESP_LOGE(TAG, "Unsupported JPEG sample method"); + ret = ESP_ERR_NOT_SUPPORTED; + goto jpeg_hw_dec_failed; + } + + out_buf = (uint8_t*)jpeg_alloc_decoder_mem(out_buf_len, &rx_mem_cfg, &rx_buffer_size); + if (out_buf == NULL || rx_buffer_size < out_buf_len) { + ESP_LOGE(TAG, "Failed to allocate memory for JPEG output buffer"); + ret = ESP_ERR_NO_MEM; + goto jpeg_hw_dec_failed; + } + + uint32_t out_size = 0; + + ESP_GOTO_ON_ERROR( + jpeg_decoder_process(jpeg_dec, &decode_cfg_rgb, bit_stream, src_len, out_buf, out_buf_len, &out_size), + jpeg_hw_dec_failed, TAG, "Failed to decode JPEG"); + + ESP_LOGD(TAG, "Expected %d bytes, got %" PRIu32 " bytes", out_buf_len, out_size); + + if (out_size != out_buf_len) { + ESP_LOGE(TAG, "Decoded image size mismatch: Expected %zu bytes, got %" PRIu32 " bytes", out_buf_len, out_size); + ret = ESP_ERR_INVALID_SIZE; + goto jpeg_hw_dec_failed; + } + + if (header_info.sample_method == JPEG_DOWN_SAMPLING_GRAY) { + // convert GRAY8 to RGB565 + uint32_t i = header_info.width * header_info.height; + do { + --i; + uint8_t r = (out_buf[i] >> 3) & 0x1F; + uint8_t g = (out_buf[i] >> 2) & 0x3F; + // b is same as r + uint16_t rgb565 = (r << 11) | (g << 5) | r; + out_buf[2 * i + 1] = (rgb565 >> 8) & 0xFF; + out_buf[2 * i] = rgb565 & 0xFF; + } while (i != 0); + out_size = header_info.width * header_info.height * 2; + ESP_LOGD(TAG, "Converted GRAY8 to RGB565, new size: %zu", out_size); + } + + ESP_LOG_BUFFER_HEXDUMP(TAG, out_buf, MIN(out_size, 256), ESP_LOG_DEBUG); + + *out = out_buf; + out_buf = NULL; + *out_len = (size_t)out_size; + jpeg_del_decoder_engine(jpeg_dec); + jpeg_dec = NULL; + heap_caps_free(bit_stream); + bit_stream = NULL; + *width = header_info.width; + *height = header_info.height; + + return ret; + +jpeg_hw_dec_failed: + if (out_buf) { + heap_caps_free(out_buf); + out_buf = NULL; + } + if (bit_stream) { + heap_caps_free(bit_stream); + bit_stream = NULL; + } + if (jpeg_dec) { + jpeg_del_decoder_engine(jpeg_dec); + jpeg_dec = NULL; + } + *out = NULL; + *out_len = 0; + *width = 0; + *height = 0; + *stride = 0; + return ret; +} +#endif // CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER + +esp_err_t jpeg_to_image(const uint8_t* src, size_t src_len, uint8_t** out, size_t* out_len, size_t* width, + size_t* height, size_t* stride) { +#ifdef CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + esp_log_level_set(TAG, ESP_LOG_DEBUG); +#endif // CONFIG_XIAOZHI_ENABLE_CAMERA_DEBUG_MODE + if (src == NULL || src_len == 0 || out == NULL || out_len == NULL || width == NULL || height == NULL || + stride == NULL) { + ESP_LOGE(TAG, "Invalid parameters"); + return ESP_ERR_INVALID_ARG; + } +#ifdef CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER + esp_err_t ret = decode_with_hardware_jpeg(src, src_len, out, out_len, width, height, stride); + if (ret == ESP_OK) { + return ret; + } + ESP_LOGW(TAG, "Failed to decode with hardware JPEG, fallback to software decoder"); + // Fallback to esp_new_jpeg +#endif + return decode_with_new_jpeg(src, src_len, out, out_len, width, height, stride); +} diff --git a/main/display/lvgl_display/jpg/jpeg_to_image.h b/main/display/lvgl_display/jpg/jpeg_to_image.h new file mode 100644 index 0000000..b33dcef --- /dev/null +++ b/main/display/lvgl_display/jpg/jpeg_to_image.h @@ -0,0 +1,62 @@ +#include "sdkconfig.h" +#ifndef CONFIG_IDF_TARGET_ESP32 + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Decodes a JPEG image from memory to raw RGB565 pixel data + * + * This function attempts to decode a JPEG image using hardware acceleration first (if enabled), + * falling back to a software decoder if hardware decoding fails or is unavailable. + * + * @param[in] src Pointer to the JPEG bitstream in memory + * @param[in] src_len Length of the JPEG bitstream in bytes + * @param[out] out Pointer to a buffer pointer that will be set to the decoded image data. + * This buffer is allocated internally and MUST be freed by the caller using heap_caps_free(). + * @param[out] out_len Pointer to a variable that will receive the size of the decoded image data in bytes + * @param[out] width Pointer to a variable that will receive the image width in pixels + * @param[out] height Pointer to a variable that will receive the image height in pixels + * @param[out] stride Pointer to a variable that will receive the image stride in bytes + * + * @return ESP_OK on successful decoding + * @return ESP_ERR_INVALID_ARG on invalid parameters + * @return ESP_ERR_NO_MEM on memory allocation failure + * @return ESP_FAIL on failure + * + * @attention Memory Management for `*out`: + * - The function allocates memory for the decoded image internally + * - On success, the caller takes ownership of this memory and SHOULD free it using heap_caps_free() + * - On failure, `*out` is guaranteed to be NULL and no freeing is required + * - Example usage: + * @code{.c} + * uint8_t *image = NULL; + * size_t len, width, height; + * if (jpeg_to_image(jpeg_data, jpeg_len, &image, &len, &width, &height)) { + * // Use image data... + * heap_caps_free(image); // Critical: use heap_caps_free + * } + * @endcode + * + * @note Configuration dependency: + * - When CONFIG_XIAOZHI_ENABLE_HARDWARE_JPEG_DECODER is enabled, hardware acceleration is attempted first + * - Both hardware and software paths allocate memory that requires heap_caps_free() for deallocation + * - The decoded image format is always RGB565 (2 bytes per pixel) + * + * @note When using hardware decoder, the decoded image dimensions might be aligned up to 16-byte boundaries. + * For YUV420 or YUV422 compressed images, both width and height will be rounded up to the nearest multiple of 16. + * See details at + * + * + */ +esp_err_t jpeg_to_image(const uint8_t* src, size_t src_len, uint8_t** out, size_t* out_len, size_t* width, + size_t* height, size_t* stride); + +#ifdef __cplusplus +} +#endif + +#endif // CONFIG_IDF_TARGET_ESP32 \ No newline at end of file diff --git a/main/display/lvgl_display/lvgl_display.cc b/main/display/lvgl_display/lvgl_display.cc new file mode 100644 index 0000000..8942a59 --- /dev/null +++ b/main/display/lvgl_display/lvgl_display.cc @@ -0,0 +1,258 @@ +#include +#include +#include +#include +#include +#include + +#include "lvgl_display.h" +#include "board.h" +#include "application.h" +#include "audio_codec.h" +#include "settings.h" +#include "assets/lang_config.h" +#include "jpg/image_to_jpeg.h" + +#define TAG "Display" + +LvglDisplay::LvglDisplay() { + // Notification timer + esp_timer_create_args_t notification_timer_args = { + .callback = [](void *arg) { + LvglDisplay *display = static_cast(arg); + DisplayLockGuard lock(display); + lv_obj_add_flag(display->notification_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_remove_flag(display->status_label_, LV_OBJ_FLAG_HIDDEN); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "notification_timer", + .skip_unhandled_events = false, + }; + ESP_ERROR_CHECK(esp_timer_create(¬ification_timer_args, ¬ification_timer_)); + + // Create a power management lock + auto ret = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, "display_update", &pm_lock_); + if (ret == ESP_ERR_NOT_SUPPORTED) { + ESP_LOGI(TAG, "Power management not supported"); + } else { + ESP_ERROR_CHECK(ret); + } +} + +LvglDisplay::~LvglDisplay() { + if (notification_timer_ != nullptr) { + esp_timer_stop(notification_timer_); + esp_timer_delete(notification_timer_); + } + + if (network_label_ != nullptr) { + lv_obj_del(network_label_); + } + if (notification_label_ != nullptr) { + lv_obj_del(notification_label_); + } + if (status_label_ != nullptr) { + lv_obj_del(status_label_); + } + if (mute_label_ != nullptr) { + lv_obj_del(mute_label_); + } + if (battery_label_ != nullptr) { + lv_obj_del(battery_label_); + } + if( low_battery_popup_ != nullptr ) { + lv_obj_del(low_battery_popup_); + } + if (pm_lock_ != nullptr) { + esp_pm_lock_delete(pm_lock_); + } +} + +void LvglDisplay::SetStatus(const char* status) { + DisplayLockGuard lock(this); + if (status_label_ == nullptr) { + return; + } + lv_label_set_text(status_label_, status); + lv_obj_remove_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + + last_status_update_time_ = std::chrono::system_clock::now(); +} + +void LvglDisplay::ShowNotification(const std::string ¬ification, int duration_ms) { + ShowNotification(notification.c_str(), duration_ms); +} + +void LvglDisplay::ShowNotification(const char* notification, int duration_ms) { + DisplayLockGuard lock(this); + if (notification_label_ == nullptr) { + return; + } + lv_label_set_text(notification_label_, notification); + lv_obj_remove_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + lv_obj_add_flag(status_label_, LV_OBJ_FLAG_HIDDEN); + + esp_timer_stop(notification_timer_); + ESP_ERROR_CHECK(esp_timer_start_once(notification_timer_, duration_ms * 1000)); +} + +void LvglDisplay::UpdateStatusBar(bool update_all) { + auto& app = Application::GetInstance(); + auto& board = Board::GetInstance(); + auto codec = board.GetAudioCodec(); + + // Update mute icon + { + DisplayLockGuard lock(this); + if (mute_label_ == nullptr) { + return; + } + + // Update icon if mute state changes + if (codec->output_volume() == 0 && !muted_) { + muted_ = true; + lv_label_set_text(mute_label_, FONT_AWESOME_VOLUME_XMARK); + } else if (codec->output_volume() > 0 && muted_) { + muted_ = false; + lv_label_set_text(mute_label_, ""); + } + } + + // Update time + if (app.GetDeviceState() == kDeviceStateIdle) { + if (last_status_update_time_ + std::chrono::seconds(10) < std::chrono::system_clock::now()) { + // Set status to clock "HH:MM" + time_t now = time(NULL); + struct tm* tm = localtime(&now); + // Check if the we have already set the time + if (tm->tm_year >= 2025 - 1900) { + char time_str[16]; + strftime(time_str, sizeof(time_str), "%H:%M", tm); + SetStatus(time_str); + } else { + ESP_LOGW(TAG, "System time is not set, tm_year: %d", tm->tm_year); + } + } + } + + esp_pm_lock_acquire(pm_lock_); + // Update battery icon + int battery_level; + bool charging, discharging; + const char* icon = nullptr; + if (board.GetBatteryLevel(battery_level, charging, discharging)) { + if (charging) { + icon = FONT_AWESOME_BATTERY_BOLT; + } else { + const char* levels[] = { + FONT_AWESOME_BATTERY_EMPTY, // 0-19% + FONT_AWESOME_BATTERY_QUARTER, // 20-39% + FONT_AWESOME_BATTERY_HALF, // 40-59% + FONT_AWESOME_BATTERY_THREE_QUARTERS, // 60-79% + FONT_AWESOME_BATTERY_FULL, // 80-99% + FONT_AWESOME_BATTERY_FULL, // 100% + }; + icon = levels[battery_level / 20]; + } + DisplayLockGuard lock(this); + if (battery_label_ != nullptr && battery_icon_ != icon) { + battery_icon_ = icon; + lv_label_set_text(battery_label_, battery_icon_); + } + + if (low_battery_popup_ != nullptr) { + if (strcmp(icon, FONT_AWESOME_BATTERY_EMPTY) == 0 && discharging) { + if (lv_obj_has_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN)) { // Show if low battery popup is hidden + lv_obj_remove_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN); + app.PlaySound(Lang::Sounds::OGG_LOW_BATTERY); + } + } else { + // Hide the low battery popup when the battery is not empty + if (!lv_obj_has_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN)) { // Hide if low battery popup is shown + lv_obj_add_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN); + } + } + } + } + + // Update network icon every 10 seconds + static int seconds_counter = 0; + if (update_all || seconds_counter++ % 10 == 0) { + // Don't read 4G network status during firmware upgrade to avoid occupying UART resources + auto device_state = Application::GetInstance().GetDeviceState(); + static const std::vector allowed_states = { + kDeviceStateIdle, + kDeviceStateStarting, + kDeviceStateWifiConfiguring, + kDeviceStateListening, + kDeviceStateActivating, + }; + if (std::find(allowed_states.begin(), allowed_states.end(), device_state) != allowed_states.end()) { + icon = board.GetNetworkStateIcon(); + if (network_label_ != nullptr && icon != nullptr && network_icon_ != icon) { + DisplayLockGuard lock(this); + network_icon_ = icon; + lv_label_set_text(network_label_, network_icon_); + } + } + } + + esp_pm_lock_release(pm_lock_); +} + +void LvglDisplay::SetPreviewImage(std::unique_ptr image) { +} + +void LvglDisplay::SetPowerSaveMode(bool on) { + if (on) { + SetChatMessage("system", ""); + SetEmotion("sleepy"); + } else { + SetChatMessage("system", ""); + SetEmotion("neutral"); + } +} + +bool LvglDisplay::SnapshotToJpeg(std::string& jpeg_data, int quality) { +#if CONFIG_LV_USE_SNAPSHOT + DisplayLockGuard lock(this); + + lv_obj_t* screen = lv_screen_active(); + lv_draw_buf_t* draw_buffer = lv_snapshot_take(screen, LV_COLOR_FORMAT_RGB565); + if (draw_buffer == nullptr) { + ESP_LOGE(TAG, "Failed to take snapshot, draw_buffer is nullptr"); + return false; + } + + // swap bytes + uint16_t* data = (uint16_t*)draw_buffer->data; + size_t pixel_count = draw_buffer->data_size / 2; + for (size_t i = 0; i < pixel_count; i++) { + data[i] = __builtin_bswap16(data[i]); + } + + // Clear output string and use callback version to avoid pre-allocating large memory blocks + jpeg_data.clear(); + + // Use callback-based JPEG encoder to further save memory + bool ret = image_to_jpeg_cb((uint8_t*)draw_buffer->data, draw_buffer->data_size, draw_buffer->header.w, draw_buffer->header.h, V4L2_PIX_FMT_RGB565, quality, + [](void *arg, size_t index, const void *data, size_t len) -> size_t { + std::string* output = static_cast(arg); + if (data && len > 0) { + output->append(static_cast(data), len); + } + return len; + }, &jpeg_data); + if (!ret) { + ESP_LOGE(TAG, "Failed to convert image to JPEG"); + } + + lv_draw_buf_destroy(draw_buffer); + return ret; +#else + ESP_LOGE(TAG, "LV_USE_SNAPSHOT is not enabled"); + return false; +#endif +} diff --git a/main/display/lvgl_display/lvgl_display.h b/main/display/lvgl_display/lvgl_display.h new file mode 100644 index 0000000..226a6ff --- /dev/null +++ b/main/display/lvgl_display/lvgl_display.h @@ -0,0 +1,53 @@ +#ifndef LVGL_DISPLAY_H +#define LVGL_DISPLAY_H + +#include "display.h" +#include "lvgl_image.h" + +#include +#include +#include +#include + +#include +#include + +class LvglDisplay : public Display { +public: + LvglDisplay(); + virtual ~LvglDisplay(); + + virtual void SetStatus(const char* status); + virtual void ShowNotification(const char* notification, int duration_ms = 3000); + virtual void ShowNotification(const std::string ¬ification, int duration_ms = 3000); + virtual void SetPreviewImage(std::unique_ptr image); + virtual void UpdateStatusBar(bool update_all = false); + virtual void SetPowerSaveMode(bool on); + virtual bool SnapshotToJpeg(std::string& jpeg_data, int quality = 80); + +protected: + esp_pm_lock_handle_t pm_lock_ = nullptr; + lv_display_t *display_ = nullptr; + + lv_obj_t *network_label_ = nullptr; + lv_obj_t *status_label_ = nullptr; + lv_obj_t *notification_label_ = nullptr; + lv_obj_t *mute_label_ = nullptr; + lv_obj_t *battery_label_ = nullptr; + lv_obj_t* low_battery_popup_ = nullptr; + lv_obj_t* low_battery_label_ = nullptr; + + const char* battery_icon_ = nullptr; + const char* network_icon_ = nullptr; + bool muted_ = false; + + std::chrono::system_clock::time_point last_status_update_time_; + esp_timer_handle_t notification_timer_ = nullptr; + + friend class DisplayLockGuard; + virtual bool Lock(int timeout_ms = 0) = 0; + virtual void Unlock() = 0; +}; + + +#endif diff --git a/main/display/lvgl_display/lvgl_font.cc b/main/display/lvgl_display/lvgl_font.cc new file mode 100644 index 0000000..b0a45c7 --- /dev/null +++ b/main/display/lvgl_display/lvgl_font.cc @@ -0,0 +1,13 @@ +#include "lvgl_font.h" +#include + + +LvglCBinFont::LvglCBinFont(void* data) { + font_ = cbin_font_create(static_cast(data)); +} + +LvglCBinFont::~LvglCBinFont() { + if (font_ != nullptr) { + cbin_font_delete(font_); + } +} \ No newline at end of file diff --git a/main/display/lvgl_display/lvgl_font.h b/main/display/lvgl_display/lvgl_font.h new file mode 100644 index 0000000..d539dc0 --- /dev/null +++ b/main/display/lvgl_display/lvgl_font.h @@ -0,0 +1,31 @@ +#pragma once + +#include + + +class LvglFont { +public: + virtual const lv_font_t* font() const = 0; + virtual ~LvglFont() = default; +}; + +// Built-in font +class LvglBuiltInFont : public LvglFont { +public: + LvglBuiltInFont(const lv_font_t* font) : font_(font) {} + virtual const lv_font_t* font() const override { return font_; } + +private: + const lv_font_t* font_; +}; + + +class LvglCBinFont : public LvglFont { +public: + LvglCBinFont(void* data); + virtual ~LvglCBinFont(); + virtual const lv_font_t* font() const override { return font_; } + +private: + lv_font_t* font_; +}; diff --git a/main/display/lvgl_display/lvgl_image.cc b/main/display/lvgl_display/lvgl_image.cc new file mode 100644 index 0000000..eefc031 --- /dev/null +++ b/main/display/lvgl_display/lvgl_image.cc @@ -0,0 +1,64 @@ +#include "lvgl_image.h" +#include + +#include +#include +#include +#include + +#define TAG "LvglImage" + + +LvglRawImage::LvglRawImage(void* data, size_t size) { + bzero(&image_dsc_, sizeof(image_dsc_)); + image_dsc_.data_size = size; + image_dsc_.data = static_cast(data); + image_dsc_.header.magic = LV_IMAGE_HEADER_MAGIC; + image_dsc_.header.cf = LV_COLOR_FORMAT_RAW_ALPHA; + image_dsc_.header.w = 0; + image_dsc_.header.h = 0; +} + +bool LvglRawImage::IsGif() const { + auto ptr = (const uint8_t*)image_dsc_.data; + return ptr[0] == 'G' && ptr[1] == 'I' && ptr[2] == 'F'; +} + +LvglCBinImage::LvglCBinImage(void* data) { + image_dsc_ = cbin_img_dsc_create(static_cast(data)); +} + +LvglCBinImage::~LvglCBinImage() { + if (image_dsc_ != nullptr) { + cbin_img_dsc_delete(image_dsc_); + } +} + +LvglAllocatedImage::LvglAllocatedImage(void* data, size_t size) { + bzero(&image_dsc_, sizeof(image_dsc_)); + image_dsc_.data_size = size; + image_dsc_.data = static_cast(data); + + if (lv_image_decoder_get_info(&image_dsc_, &image_dsc_.header) != LV_RESULT_OK) { + ESP_LOGE(TAG, "Failed to get image info, data: %p size: %u", data, size); + throw std::runtime_error("Failed to get image info"); + } +} + +LvglAllocatedImage::LvglAllocatedImage(void* data, size_t size, int width, int height, int stride, int color_format) { + bzero(&image_dsc_, sizeof(image_dsc_)); + image_dsc_.data_size = size; + image_dsc_.data = static_cast(data); + image_dsc_.header.magic = LV_IMAGE_HEADER_MAGIC; + image_dsc_.header.cf = color_format; + image_dsc_.header.w = width; + image_dsc_.header.h = height; + image_dsc_.header.stride = stride; +} + +LvglAllocatedImage::~LvglAllocatedImage() { + if (image_dsc_.data) { + heap_caps_free((void*)image_dsc_.data); + image_dsc_.data = nullptr; + } +} \ No newline at end of file diff --git a/main/display/lvgl_display/lvgl_image.h b/main/display/lvgl_display/lvgl_image.h new file mode 100644 index 0000000..0bbf39b --- /dev/null +++ b/main/display/lvgl_display/lvgl_image.h @@ -0,0 +1,53 @@ +#pragma once + +#include + + +// Wrap around lv_img_dsc_t +class LvglImage { +public: + virtual const lv_img_dsc_t* image_dsc() const = 0; + virtual bool IsGif() const { return false; } + virtual ~LvglImage() = default; +}; + + +class LvglRawImage : public LvglImage { +public: + LvglRawImage(void* data, size_t size); + virtual const lv_img_dsc_t* image_dsc() const override { return &image_dsc_; } + virtual bool IsGif() const; + +private: + lv_img_dsc_t image_dsc_; +}; + +class LvglCBinImage : public LvglImage { +public: + LvglCBinImage(void* data); + virtual ~LvglCBinImage(); + virtual const lv_img_dsc_t* image_dsc() const override { return image_dsc_; } + +private: + lv_img_dsc_t* image_dsc_ = nullptr; +}; + +class LvglSourceImage : public LvglImage { +public: + LvglSourceImage(const lv_img_dsc_t* image_dsc) : image_dsc_(image_dsc) {} + virtual const lv_img_dsc_t* image_dsc() const override { return image_dsc_; } + +private: + const lv_img_dsc_t* image_dsc_; +}; + +class LvglAllocatedImage : public LvglImage { +public: + LvglAllocatedImage(void* data, size_t size); + LvglAllocatedImage(void* data, size_t size, int width, int height, int stride, int color_format); + virtual ~LvglAllocatedImage(); + virtual const lv_img_dsc_t* image_dsc() const override { return &image_dsc_; } + +private: + lv_img_dsc_t image_dsc_; +}; \ No newline at end of file diff --git a/main/display/lvgl_display/lvgl_theme.cc b/main/display/lvgl_display/lvgl_theme.cc new file mode 100644 index 0000000..f1bdffe --- /dev/null +++ b/main/display/lvgl_display/lvgl_theme.cc @@ -0,0 +1,30 @@ +#include "lvgl_theme.h" + +LvglTheme::LvglTheme(const std::string& name) : Theme(name) { +} + +lv_color_t LvglTheme::ParseColor(const std::string& color) { + if (color.find("#") == 0) { + // Convert #112233 to lv_color_t + uint8_t r = strtol(color.substr(1, 2).c_str(), nullptr, 16); + uint8_t g = strtol(color.substr(3, 2).c_str(), nullptr, 16); + uint8_t b = strtol(color.substr(5, 2).c_str(), nullptr, 16); + return lv_color_make(r, g, b); + } + return lv_color_black(); +} + +LvglThemeManager::LvglThemeManager() { +} + +LvglTheme* LvglThemeManager::GetTheme(const std::string& theme_name) { + auto it = themes_.find(theme_name); + if (it != themes_.end()) { + return it->second; + } + return nullptr; +} + +void LvglThemeManager::RegisterTheme(const std::string& theme_name, LvglTheme* theme) { + themes_[theme_name] = theme; +} diff --git a/main/display/lvgl_display/lvgl_theme.h b/main/display/lvgl_display/lvgl_theme.h new file mode 100644 index 0000000..85527a9 --- /dev/null +++ b/main/display/lvgl_display/lvgl_theme.h @@ -0,0 +1,94 @@ +#pragma once + +#include "display.h" +#include "lvgl_image.h" +#include "lvgl_font.h" +#include "emoji_collection.h" + +#include +#include +#include +#include + + +class LvglTheme : public Theme { +public: + static lv_color_t ParseColor(const std::string& color); + + LvglTheme(const std::string& name); + + // Properties + inline lv_color_t background_color() const { return background_color_; } + inline lv_color_t text_color() const { return text_color_; } + inline lv_color_t chat_background_color() const { return chat_background_color_; } + inline lv_color_t user_bubble_color() const { return user_bubble_color_; } + inline lv_color_t assistant_bubble_color() const { return assistant_bubble_color_; } + inline lv_color_t system_bubble_color() const { return system_bubble_color_; } + inline lv_color_t system_text_color() const { return system_text_color_; } + inline lv_color_t border_color() const { return border_color_; } + inline lv_color_t low_battery_color() const { return low_battery_color_; } + inline std::shared_ptr background_image() const { return background_image_; } + inline std::shared_ptr emoji_collection() const { return emoji_collection_; } + inline std::shared_ptr text_font() const { return text_font_; } + inline std::shared_ptr icon_font() const { return icon_font_; } + inline std::shared_ptr large_icon_font() const { return large_icon_font_; } + inline int spacing(int scale) const { return spacing_ * scale; } + + inline void set_background_color(lv_color_t background) { background_color_ = background; } + inline void set_text_color(lv_color_t text) { text_color_ = text; } + inline void set_chat_background_color(lv_color_t chat_background) { chat_background_color_ = chat_background; } + inline void set_user_bubble_color(lv_color_t user_bubble) { user_bubble_color_ = user_bubble; } + inline void set_assistant_bubble_color(lv_color_t assistant_bubble) { assistant_bubble_color_ = assistant_bubble; } + inline void set_system_bubble_color(lv_color_t system_bubble) { system_bubble_color_ = system_bubble; } + inline void set_system_text_color(lv_color_t system_text) { system_text_color_ = system_text; } + inline void set_border_color(lv_color_t border) { border_color_ = border; } + inline void set_low_battery_color(lv_color_t low_battery) { low_battery_color_ = low_battery; } + inline void set_background_image(std::shared_ptr background_image) { background_image_ = background_image; } + inline void set_emoji_collection(std::shared_ptr emoji_collection) { emoji_collection_ = emoji_collection; } + inline void set_text_font(std::shared_ptr text_font) { text_font_ = text_font; } + inline void set_icon_font(std::shared_ptr icon_font) { icon_font_ = icon_font; } + inline void set_large_icon_font(std::shared_ptr large_icon_font) { large_icon_font_ = large_icon_font; } + +private: + int spacing_ = 2; + + // Colors + lv_color_t background_color_; + lv_color_t text_color_; + lv_color_t chat_background_color_; + lv_color_t user_bubble_color_; + lv_color_t assistant_bubble_color_; + lv_color_t system_bubble_color_; + lv_color_t system_text_color_; + lv_color_t border_color_; + lv_color_t low_battery_color_; + + // Background image + std::shared_ptr background_image_ = nullptr; + + // fonts + std::shared_ptr text_font_ = nullptr; + std::shared_ptr icon_font_ = nullptr; + std::shared_ptr large_icon_font_ = nullptr; + + // Emoji collection + std::shared_ptr emoji_collection_ = nullptr; +}; + + +class LvglThemeManager { +public: + static LvglThemeManager& GetInstance() { + static LvglThemeManager instance; + return instance; + } + + void RegisterTheme(const std::string& theme_name, LvglTheme* theme); + LvglTheme* GetTheme(const std::string& theme_name); + +private: + LvglThemeManager(); + void InitializeDefaultThemes(); + + std::map themes_; +}; diff --git a/main/display/oled_display.cc b/main/display/oled_display.cc new file mode 100644 index 0000000..7446914 --- /dev/null +++ b/main/display/oled_display.cc @@ -0,0 +1,396 @@ +#include "oled_display.h" +#include "assets/lang_config.h" +#include "lvgl_theme.h" +#include "lvgl_font.h" + +#include +#include + +#include +#include +#include +#include + +#define TAG "OledDisplay" + +LV_FONT_DECLARE(BUILTIN_TEXT_FONT); +LV_FONT_DECLARE(BUILTIN_ICON_FONT); +LV_FONT_DECLARE(font_awesome_30_1); + +OledDisplay::OledDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, + int width, int height, bool mirror_x, bool mirror_y) + : panel_io_(panel_io), panel_(panel) { + width_ = width; + height_ = height; + + auto text_font = std::make_shared(&BUILTIN_TEXT_FONT); + auto icon_font = std::make_shared(&BUILTIN_ICON_FONT); + auto large_icon_font = std::make_shared(&font_awesome_30_1); + + auto dark_theme = new LvglTheme("dark"); + dark_theme->set_text_font(text_font); + dark_theme->set_icon_font(icon_font); + dark_theme->set_large_icon_font(large_icon_font); + + auto& theme_manager = LvglThemeManager::GetInstance(); + theme_manager.RegisterTheme("dark", dark_theme); + current_theme_ = dark_theme; + + ESP_LOGI(TAG, "Initialize LVGL"); + lvgl_port_cfg_t port_cfg = ESP_LVGL_PORT_INIT_CONFIG(); + port_cfg.task_priority = 1; + port_cfg.task_stack = 6144; +#if CONFIG_SOC_CPU_CORES_NUM > 1 + port_cfg.task_affinity = 1; +#endif + lvgl_port_init(&port_cfg); + + ESP_LOGI(TAG, "Adding OLED display"); + const lvgl_port_display_cfg_t display_cfg = { + .io_handle = panel_io_, + .panel_handle = panel_, + .control_handle = nullptr, + .buffer_size = static_cast(width_ * height_), + .double_buffer = false, + .trans_size = 0, + .hres = static_cast(width_), + .vres = static_cast(height_), + .monochrome = true, + .rotation = { + .swap_xy = false, + .mirror_x = mirror_x, + .mirror_y = mirror_y, + }, + .flags = { + .buff_dma = 1, + .buff_spiram = 0, + .sw_rotate = 0, + .full_refresh = 0, + .direct_mode = 0, + }, + }; + + display_ = lvgl_port_add_disp(&display_cfg); + if (display_ == nullptr) { + ESP_LOGE(TAG, "Failed to add display"); + return; + } + + if (height_ == 64) { + SetupUI_128x64(); + } else { + SetupUI_128x32(); + } +} + +OledDisplay::~OledDisplay() { + if (content_ != nullptr) { + lv_obj_del(content_); + } + + bool is_128x64_layout = (top_bar_ != nullptr); + if (status_bar_ != nullptr && is_128x64_layout) { + status_label_ = nullptr; + notification_label_ = nullptr; + lv_obj_del(status_bar_); + } + if (top_bar_ != nullptr) { + network_label_ = nullptr; + mute_label_ = nullptr; + battery_label_ = nullptr; + lv_obj_del(top_bar_); + } + if (side_bar_ != nullptr) { + if (!is_128x64_layout) { + status_label_ = nullptr; + notification_label_ = nullptr; + network_label_ = nullptr; + mute_label_ = nullptr; + battery_label_ = nullptr; + } + lv_obj_del(side_bar_); + } + if (container_ != nullptr) { + lv_obj_del(container_); + } + + if (panel_ != nullptr) { + esp_lcd_panel_del(panel_); + } + if (panel_io_ != nullptr) { + esp_lcd_panel_io_del(panel_io_); + } + lvgl_port_deinit(); +} + +bool OledDisplay::Lock(int timeout_ms) { + return lvgl_port_lock(timeout_ms); +} + +void OledDisplay::Unlock() { + lvgl_port_unlock(); +} + +void OledDisplay::SetChatMessage(const char* role, const char* content) { + DisplayLockGuard lock(this); + if (chat_message_label_ == nullptr) { + return; + } + + // Replace all newlines with spaces + std::string content_str = content; + std::replace(content_str.begin(), content_str.end(), '\n', ' '); + + if (content_right_ == nullptr) { + lv_label_set_text(chat_message_label_, content_str.c_str()); + } else { + if (content == nullptr || content[0] == '\0') { + lv_obj_add_flag(content_right_, LV_OBJ_FLAG_HIDDEN); + } else { + lv_label_set_text(chat_message_label_, content_str.c_str()); + lv_obj_remove_flag(content_right_, LV_OBJ_FLAG_HIDDEN); + } + } +} + +void OledDisplay::SetupUI_128x64() { + DisplayLockGuard lock(this); + + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + auto large_icon_font = lvgl_theme->large_icon_font()->font(); + + auto screen = lv_screen_active(); + lv_obj_set_style_text_font(screen, text_font, 0); + lv_obj_set_style_text_color(screen, lv_color_black(), 0); + + /* Container */ + container_ = lv_obj_create(screen); + lv_obj_set_size(container_, LV_HOR_RES, LV_VER_RES); + lv_obj_set_flex_flow(container_, LV_FLEX_FLOW_COLUMN); + lv_obj_set_style_pad_all(container_, 0, 0); + lv_obj_set_style_border_width(container_, 0, 0); + lv_obj_set_style_pad_row(container_, 0, 0); + + /* Layer 1: Top bar - for status icons */ + top_bar_ = lv_obj_create(container_); + lv_obj_set_size(top_bar_, LV_HOR_RES, 16); + lv_obj_set_style_radius(top_bar_, 0, 0); + lv_obj_set_style_bg_opa(top_bar_, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(top_bar_, 0, 0); + lv_obj_set_style_pad_all(top_bar_, 0, 0); + lv_obj_set_flex_flow(top_bar_, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(top_bar_, LV_FLEX_ALIGN_SPACE_BETWEEN, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + lv_obj_set_scrollbar_mode(top_bar_, LV_SCROLLBAR_MODE_OFF); + + network_label_ = lv_label_create(top_bar_); + lv_label_set_text(network_label_, ""); + lv_obj_set_style_text_font(network_label_, icon_font, 0); + + lv_obj_t* right_icons = lv_obj_create(top_bar_); + lv_obj_set_size(right_icons, LV_SIZE_CONTENT, LV_SIZE_CONTENT); + lv_obj_set_style_bg_opa(right_icons, LV_OPA_TRANSP, 0); + lv_obj_set_style_border_width(right_icons, 0, 0); + lv_obj_set_style_pad_all(right_icons, 0, 0); + lv_obj_set_flex_flow(right_icons, LV_FLEX_FLOW_ROW); + lv_obj_set_flex_align(right_icons, LV_FLEX_ALIGN_END, LV_FLEX_ALIGN_CENTER, LV_FLEX_ALIGN_CENTER); + + mute_label_ = lv_label_create(right_icons); + lv_label_set_text(mute_label_, ""); + lv_obj_set_style_text_font(mute_label_, icon_font, 0); + + battery_label_ = lv_label_create(right_icons); + lv_label_set_text(battery_label_, ""); + lv_obj_set_style_text_font(battery_label_, icon_font, 0); + + /* Layer 2: Status bar - for center text labels */ + status_bar_ = lv_obj_create(screen); + lv_obj_set_size(status_bar_, LV_HOR_RES, 16); + lv_obj_set_style_radius(status_bar_, 0, 0); + lv_obj_set_style_bg_opa(status_bar_, LV_OPA_TRANSP, 0); // Transparent background + lv_obj_set_style_border_width(status_bar_, 0, 0); + lv_obj_set_style_pad_all(status_bar_, 0, 0); + lv_obj_set_scrollbar_mode(status_bar_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_layout(status_bar_, LV_LAYOUT_NONE, 0); // Use absolute positioning + lv_obj_align(status_bar_, LV_ALIGN_TOP_MID, 0, 0); // Overlap with top_bar_ + + notification_label_ = lv_label_create(status_bar_); + lv_obj_set_width(notification_label_, LV_HOR_RES); + lv_obj_set_style_text_align(notification_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_label_set_text(notification_label_, ""); + lv_obj_align(notification_label_, LV_ALIGN_CENTER, 0, 0); + lv_obj_add_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + + status_label_ = lv_label_create(status_bar_); + lv_obj_set_width(status_label_, LV_HOR_RES); + lv_label_set_long_mode(status_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_obj_set_style_text_align(status_label_, LV_TEXT_ALIGN_CENTER, 0); + lv_label_set_text(status_label_, Lang::Strings::INITIALIZING); + lv_obj_align(status_label_, LV_ALIGN_CENTER, 0, 0); + + /* Content */ + content_ = lv_obj_create(container_); + lv_obj_set_scrollbar_mode(content_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_style_radius(content_, 0, 0); + lv_obj_set_style_pad_all(content_, 0, 0); + lv_obj_set_width(content_, LV_HOR_RES); + lv_obj_set_flex_grow(content_, 1); + lv_obj_set_flex_flow(content_, LV_FLEX_FLOW_ROW); + lv_obj_set_style_flex_main_place(content_, LV_FLEX_ALIGN_CENTER, 0); + + content_left_ = lv_obj_create(content_); + lv_obj_set_size(content_left_, 32, LV_SIZE_CONTENT); + lv_obj_set_style_pad_all(content_left_, 0, 0); + lv_obj_set_style_border_width(content_left_, 0, 0); + + emotion_label_ = lv_label_create(content_left_); + lv_obj_set_style_text_font(emotion_label_, large_icon_font, 0); + lv_label_set_text(emotion_label_, FONT_AWESOME_MICROCHIP_AI); + lv_obj_center(emotion_label_); + lv_obj_set_style_pad_top(emotion_label_, 8, 0); + + content_right_ = lv_obj_create(content_); + lv_obj_set_size(content_right_, LV_SIZE_CONTENT, LV_SIZE_CONTENT); + lv_obj_set_style_pad_all(content_right_, 0, 0); + lv_obj_set_style_border_width(content_right_, 0, 0); + lv_obj_set_flex_grow(content_right_, 1); + lv_obj_add_flag(content_right_, LV_OBJ_FLAG_HIDDEN); + + chat_message_label_ = lv_label_create(content_right_); + lv_label_set_text(chat_message_label_, ""); + lv_label_set_long_mode(chat_message_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_obj_set_style_text_align(chat_message_label_, LV_TEXT_ALIGN_LEFT, 0); + lv_obj_set_width(chat_message_label_, width_ - 32); + lv_obj_set_style_pad_top(chat_message_label_, 14, 0); + + // Start scrolling subtitle after a delay + static lv_anim_t a; + lv_anim_init(&a); + lv_anim_set_delay(&a, 1000); + lv_anim_set_repeat_count(&a, LV_ANIM_REPEAT_INFINITE); + lv_obj_set_style_anim(chat_message_label_, &a, LV_PART_MAIN); + lv_obj_set_style_anim_duration(chat_message_label_, lv_anim_speed_clamped(60, 300, 60000), LV_PART_MAIN); + + low_battery_popup_ = lv_obj_create(screen); + lv_obj_set_scrollbar_mode(low_battery_popup_, LV_SCROLLBAR_MODE_OFF); + lv_obj_set_size(low_battery_popup_, LV_HOR_RES * 0.9, text_font->line_height * 2); + lv_obj_align(low_battery_popup_, LV_ALIGN_BOTTOM_MID, 0, 0); + lv_obj_set_style_bg_color(low_battery_popup_, lv_color_black(), 0); + lv_obj_set_style_radius(low_battery_popup_, 10, 0); + low_battery_label_ = lv_label_create(low_battery_popup_); + lv_label_set_text(low_battery_label_, Lang::Strings::BATTERY_NEED_CHARGE); + lv_obj_set_style_text_color(low_battery_label_, lv_color_white(), 0); + lv_obj_center(low_battery_label_); + lv_obj_add_flag(low_battery_popup_, LV_OBJ_FLAG_HIDDEN); +} + +void OledDisplay::SetupUI_128x32() { + DisplayLockGuard lock(this); + + auto lvgl_theme = static_cast(current_theme_); + auto text_font = lvgl_theme->text_font()->font(); + auto icon_font = lvgl_theme->icon_font()->font(); + auto large_icon_font = lvgl_theme->large_icon_font()->font(); + + auto screen = lv_screen_active(); + lv_obj_set_style_text_font(screen, text_font, 0); + + /* Container */ + container_ = lv_obj_create(screen); + lv_obj_set_size(container_, LV_HOR_RES, LV_VER_RES); + lv_obj_set_flex_flow(container_, LV_FLEX_FLOW_ROW); + lv_obj_set_style_pad_all(container_, 0, 0); + lv_obj_set_style_border_width(container_, 0, 0); + lv_obj_set_style_pad_column(container_, 0, 0); + + /* Emotion label on the left side */ + content_ = lv_obj_create(container_); + lv_obj_set_size(content_, 32, 32); + lv_obj_set_style_pad_all(content_, 0, 0); + lv_obj_set_style_border_width(content_, 0, 0); + lv_obj_set_style_radius(content_, 0, 0); + + emotion_label_ = lv_label_create(content_); + lv_obj_set_style_text_font(emotion_label_, large_icon_font, 0); + lv_label_set_text(emotion_label_, FONT_AWESOME_MICROCHIP_AI); + lv_obj_center(emotion_label_); + + /* Right side */ + side_bar_ = lv_obj_create(container_); + lv_obj_set_size(side_bar_, width_ - 32, 32); + lv_obj_set_flex_flow(side_bar_, LV_FLEX_FLOW_COLUMN); + lv_obj_set_style_pad_all(side_bar_, 0, 0); + lv_obj_set_style_border_width(side_bar_, 0, 0); + lv_obj_set_style_radius(side_bar_, 0, 0); + lv_obj_set_style_pad_row(side_bar_, 0, 0); + + /* Status bar */ + status_bar_ = lv_obj_create(side_bar_); + lv_obj_set_size(status_bar_, width_ - 32, 16); + lv_obj_set_style_radius(status_bar_, 0, 0); + lv_obj_set_flex_flow(status_bar_, LV_FLEX_FLOW_ROW); + lv_obj_set_style_pad_all(status_bar_, 0, 0); + lv_obj_set_style_border_width(status_bar_, 0, 0); + lv_obj_set_style_pad_column(status_bar_, 0, 0); + + status_label_ = lv_label_create(status_bar_); + lv_obj_set_flex_grow(status_label_, 1); + lv_obj_set_style_pad_left(status_label_, 2, 0); + lv_label_set_text(status_label_, Lang::Strings::INITIALIZING); + + notification_label_ = lv_label_create(status_bar_); + lv_obj_set_flex_grow(notification_label_, 1); + lv_obj_set_style_pad_left(notification_label_, 2, 0); + lv_label_set_text(notification_label_, ""); + lv_obj_add_flag(notification_label_, LV_OBJ_FLAG_HIDDEN); + + mute_label_ = lv_label_create(status_bar_); + lv_label_set_text(mute_label_, ""); + lv_obj_set_style_text_font(mute_label_, icon_font, 0); + + network_label_ = lv_label_create(status_bar_); + lv_label_set_text(network_label_, ""); + lv_obj_set_style_text_font(network_label_, icon_font, 0); + + battery_label_ = lv_label_create(status_bar_); + lv_label_set_text(battery_label_, ""); + lv_obj_set_style_text_font(battery_label_, icon_font, 0); + + chat_message_label_ = lv_label_create(side_bar_); + lv_obj_set_size(chat_message_label_, width_ - 32, LV_SIZE_CONTENT); + lv_obj_set_style_pad_left(chat_message_label_, 2, 0); + lv_label_set_long_mode(chat_message_label_, LV_LABEL_LONG_SCROLL_CIRCULAR); + lv_label_set_text(chat_message_label_, ""); + + // Start scrolling subtitle after a delay + static lv_anim_t a; + lv_anim_init(&a); + lv_anim_set_delay(&a, 1000); + lv_anim_set_repeat_count(&a, LV_ANIM_REPEAT_INFINITE); + lv_obj_set_style_anim(chat_message_label_, &a, LV_PART_MAIN); + lv_obj_set_style_anim_duration(chat_message_label_, lv_anim_speed_clamped(60, 300, 60000), LV_PART_MAIN); +} + +void OledDisplay::SetEmotion(const char* emotion) { + const char* utf8 = font_awesome_get_utf8(emotion); + DisplayLockGuard lock(this); + if (emotion_label_ == nullptr) { + return; + } + if (utf8 != nullptr) { + lv_label_set_text(emotion_label_, utf8); + } else { + lv_label_set_text(emotion_label_, FONT_AWESOME_NEUTRAL); + } +} + +void OledDisplay::SetTheme(Theme* theme) { + DisplayLockGuard lock(this); + + auto lvgl_theme = static_cast(theme); + auto text_font = lvgl_theme->text_font()->font(); + + auto screen = lv_screen_active(); + lv_obj_set_style_text_font(screen, text_font, 0); +} diff --git a/main/display/oled_display.h b/main/display/oled_display.h new file mode 100644 index 0000000..c7f4077 --- /dev/null +++ b/main/display/oled_display.h @@ -0,0 +1,40 @@ +#ifndef OLED_DISPLAY_H +#define OLED_DISPLAY_H + +#include "lvgl_display.h" + +#include +#include + + +class OledDisplay : public LvglDisplay { +private: + esp_lcd_panel_io_handle_t panel_io_ = nullptr; + esp_lcd_panel_handle_t panel_ = nullptr; + + lv_obj_t* top_bar_ = nullptr; + lv_obj_t* status_bar_ = nullptr; + lv_obj_t* content_ = nullptr; + lv_obj_t* content_left_ = nullptr; + lv_obj_t* content_right_ = nullptr; + lv_obj_t* container_ = nullptr; + lv_obj_t* side_bar_ = nullptr; + lv_obj_t *emotion_label_ = nullptr; + lv_obj_t* chat_message_label_ = nullptr; + + virtual bool Lock(int timeout_ms = 0) override; + virtual void Unlock() override; + + void SetupUI_128x64(); + void SetupUI_128x32(); + +public: + OledDisplay(esp_lcd_panel_io_handle_t panel_io, esp_lcd_panel_handle_t panel, int width, int height, bool mirror_x, bool mirror_y); + ~OledDisplay(); + + virtual void SetChatMessage(const char* role, const char* content) override; + virtual void SetEmotion(const char* emotion) override; + virtual void SetTheme(Theme* theme) override; +}; + +#endif // OLED_DISPLAY_H diff --git a/main/idf_component.yml b/main/idf_component.yml new file mode 100644 index 0000000..658d51f --- /dev/null +++ b/main/idf_component.yml @@ -0,0 +1,110 @@ +## IDF Component Manager Manifest File +dependencies: + waveshare/esp_lcd_sh8601: 1.0.2 + espressif/esp_lcd_ili9341: ==1.2.0 + espressif/esp_lcd_gc9a01: ==2.0.1 + espressif/esp_lcd_st77916: ^1.0.1 + espressif/esp_lcd_axs15231b: ^1.0.0 + + espressif/esp_lcd_st7701: + version: ^1.1.4 + rules: + - if: target in [esp32s3, esp32p4] + espressif/esp_lcd_st7796: + version: 1.3.5 + rules: + - if: target in [esp32, esp32s2, esp32s3, esp32p4] + espressif/esp_lcd_spd2010: ==1.0.2 + espressif/esp_io_expander_tca9554: ==2.0.0 + espressif/esp_lcd_panel_io_additions: ^1.0.1 + 78/esp_lcd_nv3023: ~1.0.0 + 78/esp-wifi-connect: ~2.6.2 + 78/esp-opus-encoder: ~2.4.1 + 78/esp-ml307: ~3.5.1 + 78/xiaozhi-fonts: ~1.5.5 + espressif/led_strip: ~3.0.1 + espressif/esp_codec_dev: ~1.5 + espressif/esp-sr: ~2.2.0 + espressif/button: ~4.1.3 + espressif/knob: ^1.0.0 + espressif/esp_video: + version: ==1.3.1 # for compatibility. update version may need to modify this project code. + rules: + - if: target not in [esp32] + espressif/esp_image_effects: + version: ^1.0.1 + rules: + - if: target not in [esp32] + espressif/esp_lcd_touch_ft5x06: ~1.0.7 + espressif/esp_lcd_touch_gt911: ^1 + espressif/esp_lcd_touch_gt1151: ^1 + waveshare/esp_lcd_touch_cst9217: ^1.0.3 + espressif/esp_lcd_touch_cst816s: ^1.0.6 + lvgl/lvgl: ~9.3.0 + esp_lvgl_port: ~2.6.0 + espressif/esp_io_expander_tca95xx_16bit: ^2.0.0 + espressif2022/image_player: ^1.1.1 + espressif2022/esp_emote_gfx: ^1.1.2 + espressif/adc_mic: ^0.2.1 + espressif/esp_mmap_assets: '>=1.2' + txp666/otto-emoji-gif-component: + version: ^1.0.3 + rules: + - if: target in [esp32s3] + espressif/adc_battery_estimation: ^0.2.0 + espressif/esp_new_jpeg: ^0.6.1 + + # SenseCAP Watcher Board + wvirgil123/sscma_client: + version: 1.0.2 + rules: + - if: target in [esp32s3] + + tny-robotics/sh1106-esp-idf: ^1.0.0 + waveshare/esp_lcd_jd9365_10_1: + version: '*' + rules: + - if: target in [esp32p4] + waveshare/esp_lcd_st7703: + version: '*' + rules: + - if: target in [esp32p4] + espressif/esp32_p4_function_ev_board: + version: ^5.0.3 + rules: + - if: target in [esp32p4] + espressif/esp_lcd_ili9881c: + version: ^1.0.1 + rules: + - if: target in [esp32p4] + espressif/esp_lcd_ek79007: + version: ^1.0.3 + rules: + - if: target in [esp32p4] + espressif/esp_hosted: + version: 2.0.17 + rules: + - if: target in [esp32h2, esp32p4] + espressif/esp_wifi_remote: + version: '*' + rules: + - if: target in [esp32p4] + espfriends/servo_dog_ctrl: + version: ^0.1.8 + rules: + - if: target in [esp32c3] + + llgok/cpp_bus_driver: + version: 1.1.0 + rules: + - if: target in [esp32p4] + + espressif/bmi270_sensor: + version: ^0.1.0 + rules: + - if: target in [esp32s3, esp32c5] + + ## Required IDF version + idf: + version: '>=5.4.0' + espressif/esp_lcd_touch_st7123: ^1.0.0 diff --git a/main/led/circular_strip.cc b/main/led/circular_strip.cc new file mode 100644 index 0000000..cb428ad --- /dev/null +++ b/main/led/circular_strip.cc @@ -0,0 +1,233 @@ +#include "circular_strip.h" +#include "application.h" +#include + +#define TAG "CircularStrip" + +#define BLINK_INFINITE -1 + +CircularStrip::CircularStrip(gpio_num_t gpio, uint8_t max_leds) : max_leds_(max_leds) { + // If the gpio is not connected, you should use NoLed class + assert(gpio != GPIO_NUM_NC); + + colors_.resize(max_leds_); + + led_strip_config_t strip_config = {}; + strip_config.strip_gpio_num = gpio; + strip_config.max_leds = max_leds_; + strip_config.color_component_format = LED_STRIP_COLOR_COMPONENT_FMT_GRB; + strip_config.led_model = LED_MODEL_WS2812; + + led_strip_rmt_config_t rmt_config = {}; + rmt_config.resolution_hz = 10 * 1000 * 1000; // 10MHz + + ESP_ERROR_CHECK(led_strip_new_rmt_device(&strip_config, &rmt_config, &led_strip_)); + led_strip_clear(led_strip_); + + esp_timer_create_args_t strip_timer_args = { + .callback = [](void *arg) { + auto strip = static_cast(arg); + std::lock_guard lock(strip->mutex_); + if (strip->strip_callback_ != nullptr) { + strip->strip_callback_(); + } + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "strip_timer", + .skip_unhandled_events = false, + }; + ESP_ERROR_CHECK(esp_timer_create(&strip_timer_args, &strip_timer_)); +} + +CircularStrip::~CircularStrip() { + esp_timer_stop(strip_timer_); + if (led_strip_ != nullptr) { + led_strip_del(led_strip_); + } +} + + +void CircularStrip::SetAllColor(StripColor color) { + std::lock_guard lock(mutex_); + esp_timer_stop(strip_timer_); + for (int i = 0; i < max_leds_; i++) { + colors_[i] = color; + led_strip_set_pixel(led_strip_, i, color.red, color.green, color.blue); + } + led_strip_refresh(led_strip_); +} + +void CircularStrip::SetSingleColor(uint8_t index, StripColor color) { + std::lock_guard lock(mutex_); + esp_timer_stop(strip_timer_); + colors_[index] = color; + led_strip_set_pixel(led_strip_, index, color.red, color.green, color.blue); + led_strip_refresh(led_strip_); +} + +void CircularStrip::Blink(StripColor color, int interval_ms) { + for (int i = 0; i < max_leds_; i++) { + colors_[i] = color; + } + StartStripTask(interval_ms, [this]() { + static bool on = true; + if (on) { + for (int i = 0; i < max_leds_; i++) { + led_strip_set_pixel(led_strip_, i, colors_[i].red, colors_[i].green, colors_[i].blue); + } + led_strip_refresh(led_strip_); + } else { + led_strip_clear(led_strip_); + } + on = !on; + }); +} + +void CircularStrip::FadeOut(int interval_ms) { + StartStripTask(interval_ms, [this]() { + bool all_off = true; + for (int i = 0; i < max_leds_; i++) { + colors_[i].red /= 2; + colors_[i].green /= 2; + colors_[i].blue /= 2; + if (colors_[i].red != 0 || colors_[i].green != 0 || colors_[i].blue != 0) { + all_off = false; + } + led_strip_set_pixel(led_strip_, i, colors_[i].red, colors_[i].green, colors_[i].blue); + } + if (all_off) { + led_strip_clear(led_strip_); + esp_timer_stop(strip_timer_); + } else { + led_strip_refresh(led_strip_); + } + }); +} + +void CircularStrip::Breathe(StripColor low, StripColor high, int interval_ms) { + StartStripTask(interval_ms, [this, low, high]() { + static bool increase = true; + static StripColor color = low; + if (increase) { + if (color.red < high.red) { + color.red++; + } + if (color.green < high.green) { + color.green++; + } + if (color.blue < high.blue) { + color.blue++; + } + if (color.red == high.red && color.green == high.green && color.blue == high.blue) { + increase = false; + } + } else { + if (color.red > low.red) { + color.red--; + } + if (color.green > low.green) { + color.green--; + } + if (color.blue > low.blue) { + color.blue--; + } + if (color.red == low.red && color.green == low.green && color.blue == low.blue) { + increase = true; + } + } + for (int i = 0; i < max_leds_; i++) { + led_strip_set_pixel(led_strip_, i, color.red, color.green, color.blue); + } + led_strip_refresh(led_strip_); + }); +} + +void CircularStrip::Scroll(StripColor low, StripColor high, int length, int interval_ms) { + for (int i = 0; i < max_leds_; i++) { + colors_[i] = low; + } + StartStripTask(interval_ms, [this, low, high, length]() { + static int offset = 0; + for (int i = 0; i < max_leds_; i++) { + colors_[i] = low; + } + for (int j = 0; j < length; j++) { + int i = (offset + j) % max_leds_; + colors_[i] = high; + } + for (int i = 0; i < max_leds_; i++) { + led_strip_set_pixel(led_strip_, i, colors_[i].red, colors_[i].green, colors_[i].blue); + } + led_strip_refresh(led_strip_); + offset = (offset + 1) % max_leds_; + }); +} + +void CircularStrip::StartStripTask(int interval_ms, std::function cb) { + if (led_strip_ == nullptr) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(strip_timer_); + + strip_callback_ = cb; + esp_timer_start_periodic(strip_timer_, interval_ms * 1000); +} + +void CircularStrip::SetBrightness(uint8_t default_brightness, uint8_t low_brightness) { + default_brightness_ = default_brightness; + low_brightness_ = low_brightness; + OnStateChanged(); +} + +void CircularStrip::OnStateChanged() { + auto& app = Application::GetInstance(); + auto device_state = app.GetDeviceState(); + switch (device_state) { + case kDeviceStateStarting: { + StripColor low = { 0, 0, 0 }; + StripColor high = { low_brightness_, low_brightness_, default_brightness_ }; + Scroll(low, high, 3, 100); + break; + } + case kDeviceStateWifiConfiguring: { + StripColor color = { low_brightness_, low_brightness_, default_brightness_ }; + Blink(color, 500); + break; + } + case kDeviceStateIdle: + FadeOut(50); + break; + case kDeviceStateConnecting: { + StripColor color = { low_brightness_, low_brightness_, default_brightness_ }; + SetAllColor(color); + break; + } + case kDeviceStateListening: + case kDeviceStateAudioTesting: { + StripColor color = { default_brightness_, low_brightness_, low_brightness_ }; + SetAllColor(color); + break; + } + case kDeviceStateSpeaking: { + StripColor color = { low_brightness_, default_brightness_, low_brightness_ }; + SetAllColor(color); + break; + } + case kDeviceStateUpgrading: { + StripColor color = { low_brightness_, default_brightness_, low_brightness_ }; + Blink(color, 100); + break; + } + case kDeviceStateActivating: { + StripColor color = { low_brightness_, default_brightness_, low_brightness_ }; + Blink(color, 500); + break; + } + default: + ESP_LOGW(TAG, "Unknown led strip event: %d", device_state); + return; + } +} diff --git a/main/led/circular_strip.h b/main/led/circular_strip.h new file mode 100644 index 0000000..d5d6c22 --- /dev/null +++ b/main/led/circular_strip.h @@ -0,0 +1,51 @@ +#ifndef _CIRCULAR_STRIP_H_ +#define _CIRCULAR_STRIP_H_ + +#include "led.h" +#include +#include +#include +#include +#include +#include + +#define DEFAULT_BRIGHTNESS 32 +#define LOW_BRIGHTNESS 4 + +struct StripColor { + uint8_t red = 0, green = 0, blue = 0; +}; + +class CircularStrip : public Led { +public: + CircularStrip(gpio_num_t gpio, uint8_t max_leds); + virtual ~CircularStrip(); + + void OnStateChanged() override; + void SetBrightness(uint8_t default_brightness, uint8_t low_brightness); + void SetAllColor(StripColor color); + void SetSingleColor(uint8_t index, StripColor color); + void Blink(StripColor color, int interval_ms); + void Breathe(StripColor low, StripColor high, int interval_ms); + void Scroll(StripColor low, StripColor high, int length, int interval_ms); + +private: + std::mutex mutex_; + TaskHandle_t blink_task_ = nullptr; + led_strip_handle_t led_strip_ = nullptr; + int max_leds_ = 0; + std::vector colors_; + int blink_counter_ = 0; + int blink_interval_ms_ = 0; + esp_timer_handle_t strip_timer_ = nullptr; + std::function strip_callback_ = nullptr; + + uint8_t default_brightness_ = DEFAULT_BRIGHTNESS; + uint8_t low_brightness_ = LOW_BRIGHTNESS; + + void StartStripTask(int interval_ms, std::function cb); + void Rainbow(StripColor low, StripColor high, int interval_ms); + void FadeOut(int interval_ms); +}; + +#endif // _CIRCULAR_STRIP_H_ diff --git a/main/led/gpio_led.cc b/main/led/gpio_led.cc new file mode 100644 index 0000000..c3c3266 --- /dev/null +++ b/main/led/gpio_led.cc @@ -0,0 +1,249 @@ +#include "gpio_led.h" +#include "application.h" +#include "device_state.h" +#include + +#define TAG "GpioLed" + +#define DEFAULT_BRIGHTNESS 50 +#define HIGH_BRIGHTNESS 100 +#define LOW_BRIGHTNESS 10 + +#define IDLE_BRIGHTNESS 5 +#define SPEAKING_BRIGHTNESS 75 +#define UPGRADING_BRIGHTNESS 25 +#define ACTIVATING_BRIGHTNESS 35 + +#define BLINK_INFINITE -1 + +// GPIO_LED +#define LEDC_LS_TIMER LEDC_TIMER_1 +#define LEDC_LS_MODE LEDC_LOW_SPEED_MODE +#define LEDC_LS_CH0_CHANNEL LEDC_CHANNEL_0 + +#define LEDC_DUTY (8191) +#define LEDC_FADE_TIME (1000) +// GPIO_LED + +GpioLed::GpioLed(gpio_num_t gpio) + : GpioLed(gpio, 0, LEDC_LS_TIMER, LEDC_LS_CH0_CHANNEL) { +} + +GpioLed::GpioLed(gpio_num_t gpio, int output_invert) + : GpioLed(gpio, output_invert, LEDC_LS_TIMER, LEDC_LS_CH0_CHANNEL) { +} + +GpioLed::GpioLed(gpio_num_t gpio, int output_invert, ledc_timer_t timer_num, ledc_channel_t channel) { + // If the gpio is not connected, you should use NoLed class + assert(gpio != GPIO_NUM_NC); + + /* + * Prepare and set configuration of timers + * that will be used by LED Controller + */ + ledc_timer_config_t ledc_timer = {}; + ledc_timer.duty_resolution = LEDC_TIMER_13_BIT; // resolution of PWM duty + ledc_timer.freq_hz = 4000; // frequency of PWM signal + ledc_timer.speed_mode = LEDC_LS_MODE; // timer mode + ledc_timer.timer_num = timer_num; // timer index + ledc_timer.clk_cfg = LEDC_AUTO_CLK; // Auto select the source clock + + ESP_ERROR_CHECK(ledc_timer_config(&ledc_timer)); + + ledc_channel_.channel = channel, + ledc_channel_.duty = 0, + ledc_channel_.gpio_num = gpio, + ledc_channel_.speed_mode = LEDC_LS_MODE, + ledc_channel_.hpoint = 0, + ledc_channel_.timer_sel = timer_num, + ledc_channel_.flags.output_invert = output_invert & 0x01, + + // Set LED Controller with previously prepared configuration + ledc_channel_config(&ledc_channel_); + + // Initialize fade service. + ledc_fade_func_install(0); + + // When the callback registered by ledc_cb_degister is called, run led ->OnFadeEnd() + ledc_cbs_t ledc_callbacks = { + .fade_cb = FadeCallback + }; + ledc_cb_register(ledc_channel_.speed_mode, ledc_channel_.channel, &ledc_callbacks, this); + + esp_timer_create_args_t blink_timer_args = { + .callback = [](void *arg) { + auto led = static_cast(arg); + led->OnBlinkTimer(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "Blink Timer", + .skip_unhandled_events = false, + }; + ESP_ERROR_CHECK(esp_timer_create(&blink_timer_args, &blink_timer_)); + + ledc_initialized_ = true; +} + +GpioLed::~GpioLed() { + esp_timer_stop(blink_timer_); + if (ledc_initialized_) { + ledc_fade_stop(ledc_channel_.speed_mode, ledc_channel_.channel); + ledc_fade_func_uninstall(); + } +} + + +void GpioLed::SetBrightness(uint8_t brightness) { + if (brightness == 100) { + duty_ = LEDC_DUTY; + } else { + duty_ = brightness * LEDC_DUTY / 100; + } +} + +void GpioLed::TurnOn() { + if (!ledc_initialized_) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + ledc_fade_stop(ledc_channel_.speed_mode, ledc_channel_.channel); + ledc_set_duty(ledc_channel_.speed_mode, ledc_channel_.channel, duty_); + ledc_update_duty(ledc_channel_.speed_mode, ledc_channel_.channel); +} + +void GpioLed::TurnOff() { + if (!ledc_initialized_) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + ledc_fade_stop(ledc_channel_.speed_mode, ledc_channel_.channel); + ledc_set_duty(ledc_channel_.speed_mode, ledc_channel_.channel, 0); + ledc_update_duty(ledc_channel_.speed_mode, ledc_channel_.channel); +} + +void GpioLed::BlinkOnce() { + Blink(1, 100); +} + +void GpioLed::Blink(int times, int interval_ms) { + StartBlinkTask(times, interval_ms); +} + +void GpioLed::StartContinuousBlink(int interval_ms) { + StartBlinkTask(BLINK_INFINITE, interval_ms); +} + +void GpioLed::StartBlinkTask(int times, int interval_ms) { + if (!ledc_initialized_) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + ledc_fade_stop(ledc_channel_.speed_mode, ledc_channel_.channel); + + blink_counter_ = times * 2; + blink_interval_ms_ = interval_ms; + esp_timer_start_periodic(blink_timer_, interval_ms * 1000); +} + +void GpioLed::OnBlinkTimer() { + std::lock_guard lock(mutex_); + blink_counter_--; + if (blink_counter_ & 1) { + ledc_set_duty(ledc_channel_.speed_mode, ledc_channel_.channel, duty_); + } else { + ledc_set_duty(ledc_channel_.speed_mode, ledc_channel_.channel, 0); + + if (blink_counter_ == 0) { + esp_timer_stop(blink_timer_); + } + } + ledc_update_duty(ledc_channel_.speed_mode, ledc_channel_.channel); +} + +void GpioLed::StartFadeTask() { + if (!ledc_initialized_) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + ledc_fade_stop(ledc_channel_.speed_mode, ledc_channel_.channel); + fade_up_ = true; + ledc_set_fade_with_time(ledc_channel_.speed_mode, + ledc_channel_.channel, LEDC_DUTY, LEDC_FADE_TIME); + ledc_fade_start(ledc_channel_.speed_mode, + ledc_channel_.channel, LEDC_FADE_NO_WAIT); +} + +void GpioLed::OnFadeEnd() { + std::lock_guard lock(mutex_); + fade_up_ = !fade_up_; + ledc_set_fade_with_time(ledc_channel_.speed_mode, + ledc_channel_.channel, fade_up_ ? LEDC_DUTY : 0, LEDC_FADE_TIME); + ledc_fade_start(ledc_channel_.speed_mode, + ledc_channel_.channel, LEDC_FADE_NO_WAIT); +} + +bool IRAM_ATTR GpioLed::FadeCallback(const ledc_cb_param_t *param, void *user_arg) { + if (param->event == LEDC_FADE_END_EVT) { + auto led = static_cast(user_arg); + led->OnFadeEnd(); + } + return true; +} + +void GpioLed::OnStateChanged() { + auto& app = Application::GetInstance(); + auto device_state = app.GetDeviceState(); + switch (device_state) { + case kDeviceStateStarting: + SetBrightness(DEFAULT_BRIGHTNESS); + StartContinuousBlink(100); + break; + case kDeviceStateWifiConfiguring: + SetBrightness(DEFAULT_BRIGHTNESS); + StartContinuousBlink(500); + break; + case kDeviceStateIdle: + SetBrightness(IDLE_BRIGHTNESS); + TurnOn(); + // TurnOff(); + break; + case kDeviceStateConnecting: + SetBrightness(DEFAULT_BRIGHTNESS); + TurnOn(); + break; + case kDeviceStateListening: + case kDeviceStateAudioTesting: + if (app.IsVoiceDetected()) { + SetBrightness(HIGH_BRIGHTNESS); + } else { + SetBrightness(LOW_BRIGHTNESS); + } + // TurnOn(); + StartFadeTask(); + break; + case kDeviceStateSpeaking: + SetBrightness(SPEAKING_BRIGHTNESS); + TurnOn(); + break; + case kDeviceStateUpgrading: + SetBrightness(UPGRADING_BRIGHTNESS); + StartContinuousBlink(100); + break; + case kDeviceStateActivating: + SetBrightness(ACTIVATING_BRIGHTNESS); + StartContinuousBlink(500); + break; + default: + ESP_LOGE(TAG, "Unknown gpio led event: %d", device_state); + return; + } +} diff --git a/main/led/gpio_led.h b/main/led/gpio_led.h new file mode 100644 index 0000000..4d1f5db --- /dev/null +++ b/main/led/gpio_led.h @@ -0,0 +1,47 @@ +#ifndef _GPIO_LED_H_ +#define _GPIO_LED_H_ + +#include +#include +#include "led.h" +#include +#include +#include +#include +#include + +class GpioLed : public Led { + public: + GpioLed(gpio_num_t gpio); + GpioLed(gpio_num_t gpio, int output_invert); + GpioLed(gpio_num_t gpio, int output_invert, ledc_timer_t timer_num, ledc_channel_t channel); + virtual ~GpioLed(); + + void OnStateChanged() override; + void TurnOn(); + void TurnOff(); + void SetBrightness(uint8_t brightness); + + private: + std::mutex mutex_; + TaskHandle_t blink_task_ = nullptr; + ledc_channel_config_t ledc_channel_ = {0}; + bool ledc_initialized_ = false; + uint32_t duty_ = 0; + int blink_counter_ = 0; + int blink_interval_ms_ = 0; + esp_timer_handle_t blink_timer_ = nullptr; + bool fade_up_ = true; + + void StartBlinkTask(int times, int interval_ms); + void OnBlinkTimer(); + + void BlinkOnce(); + void Blink(int times, int interval_ms); + void StartContinuousBlink(int interval_ms); + void StartFadeTask(); + void OnFadeEnd(); + static bool IRAM_ATTR FadeCallback(const ledc_cb_param_t *param, void *user_arg); +}; + +#endif // _GPIO_LED_H_ diff --git a/main/led/led.h b/main/led/led.h new file mode 100644 index 0000000..251fd6a --- /dev/null +++ b/main/led/led.h @@ -0,0 +1,17 @@ +#ifndef _LED_H_ +#define _LED_H_ + +class Led { +public: + virtual ~Led() = default; + // Set the led state based on the device state + virtual void OnStateChanged() = 0; +}; + + +class NoLed : public Led { +public: + virtual void OnStateChanged() override {} +}; + +#endif // _LED_H_ diff --git a/main/led/single_led.cc b/main/led/single_led.cc new file mode 100644 index 0000000..338af0a --- /dev/null +++ b/main/led/single_led.cc @@ -0,0 +1,163 @@ +#include "single_led.h" +#include "application.h" +#include + +#define TAG "SingleLed" + +#define DEFAULT_BRIGHTNESS 4 +#define HIGH_BRIGHTNESS 16 +#define LOW_BRIGHTNESS 2 + +#define BLINK_INFINITE -1 + + +SingleLed::SingleLed(gpio_num_t gpio) { + // If the gpio is not connected, you should use NoLed class + assert(gpio != GPIO_NUM_NC); + + led_strip_config_t strip_config = {}; + strip_config.strip_gpio_num = gpio; + strip_config.max_leds = 1; + strip_config.color_component_format = LED_STRIP_COLOR_COMPONENT_FMT_GRB; + strip_config.led_model = LED_MODEL_WS2812; + + led_strip_rmt_config_t rmt_config = {}; + rmt_config.resolution_hz = 10 * 1000 * 1000; // 10MHz + + ESP_ERROR_CHECK(led_strip_new_rmt_device(&strip_config, &rmt_config, &led_strip_)); + led_strip_clear(led_strip_); + + esp_timer_create_args_t blink_timer_args = { + .callback = [](void *arg) { + auto led = static_cast(arg); + led->OnBlinkTimer(); + }, + .arg = this, + .dispatch_method = ESP_TIMER_TASK, + .name = "blink_timer", + .skip_unhandled_events = false, + }; + ESP_ERROR_CHECK(esp_timer_create(&blink_timer_args, &blink_timer_)); +} + +SingleLed::~SingleLed() { + esp_timer_stop(blink_timer_); + if (led_strip_ != nullptr) { + led_strip_del(led_strip_); + } +} + + +void SingleLed::SetColor(uint8_t r, uint8_t g, uint8_t b) { + r_ = r; + g_ = g; + b_ = b; +} + +void SingleLed::TurnOn() { + if (led_strip_ == nullptr) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + led_strip_set_pixel(led_strip_, 0, r_, g_, b_); + led_strip_refresh(led_strip_); +} + +void SingleLed::TurnOff() { + if (led_strip_ == nullptr) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + led_strip_clear(led_strip_); +} + +void SingleLed::BlinkOnce() { + Blink(1, 100); +} + +void SingleLed::Blink(int times, int interval_ms) { + StartBlinkTask(times, interval_ms); +} + +void SingleLed::StartContinuousBlink(int interval_ms) { + StartBlinkTask(BLINK_INFINITE, interval_ms); +} + +void SingleLed::StartBlinkTask(int times, int interval_ms) { + if (led_strip_ == nullptr) { + return; + } + + std::lock_guard lock(mutex_); + esp_timer_stop(blink_timer_); + + blink_counter_ = times * 2; + blink_interval_ms_ = interval_ms; + esp_timer_start_periodic(blink_timer_, interval_ms * 1000); +} + +void SingleLed::OnBlinkTimer() { + std::lock_guard lock(mutex_); + blink_counter_--; + if (blink_counter_ & 1) { + led_strip_set_pixel(led_strip_, 0, r_, g_, b_); + led_strip_refresh(led_strip_); + } else { + led_strip_clear(led_strip_); + + if (blink_counter_ == 0) { + esp_timer_stop(blink_timer_); + } + } +} + + +void SingleLed::OnStateChanged() { + auto& app = Application::GetInstance(); + auto device_state = app.GetDeviceState(); + switch (device_state) { + case kDeviceStateStarting: + SetColor(0, 0, DEFAULT_BRIGHTNESS); + StartContinuousBlink(100); + break; + case kDeviceStateWifiConfiguring: + SetColor(0, 0, DEFAULT_BRIGHTNESS); + StartContinuousBlink(500); + break; + case kDeviceStateIdle: + TurnOff(); + break; + case kDeviceStateConnecting: + SetColor(0, 0, DEFAULT_BRIGHTNESS); + TurnOn(); + break; + case kDeviceStateListening: + case kDeviceStateAudioTesting: + if (app.IsVoiceDetected()) { + SetColor(HIGH_BRIGHTNESS, 0, 0); + } else { + SetColor(LOW_BRIGHTNESS, 0, 0); + } + TurnOn(); + break; + case kDeviceStateSpeaking: + SetColor(0, DEFAULT_BRIGHTNESS, 0); + TurnOn(); + break; + case kDeviceStateUpgrading: + SetColor(0, DEFAULT_BRIGHTNESS, 0); + StartContinuousBlink(100); + break; + case kDeviceStateActivating: + SetColor(0, DEFAULT_BRIGHTNESS, 0); + StartContinuousBlink(500); + break; + default: + ESP_LOGW(TAG, "Unknown led strip event: %d", device_state); + return; + } +} diff --git a/main/led/single_led.h b/main/led/single_led.h new file mode 100644 index 0000000..b949f74 --- /dev/null +++ b/main/led/single_led.h @@ -0,0 +1,38 @@ +#ifndef _SINGLE_LED_H_ +#define _SINGLE_LED_H_ + +#include "led.h" +#include +#include +#include +#include +#include + +class SingleLed : public Led { +public: + SingleLed(gpio_num_t gpio); + virtual ~SingleLed(); + + void OnStateChanged() override; + +private: + std::mutex mutex_; + TaskHandle_t blink_task_ = nullptr; + led_strip_handle_t led_strip_ = nullptr; + uint8_t r_ = 0, g_ = 0, b_ = 0; + int blink_counter_ = 0; + int blink_interval_ms_ = 0; + esp_timer_handle_t blink_timer_ = nullptr; + + void StartBlinkTask(int times, int interval_ms); + void OnBlinkTimer(); + + void BlinkOnce(); + void Blink(int times, int interval_ms); + void StartContinuousBlink(int interval_ms); + void TurnOn(); + void TurnOff(); + void SetColor(uint8_t r, uint8_t g, uint8_t b); +}; + +#endif // _SINGLE_LED_H_ diff --git a/main/main.cc b/main/main.cc new file mode 100755 index 0000000..0483092 --- /dev/null +++ b/main/main.cc @@ -0,0 +1,34 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include "application.h" +#include "system_info.h" +#include "uart_component.h" + +#define TAG "main" + +extern "C" void app_main(void) +{ + uart_init_component(); + // Initialize the default event loop + ESP_ERROR_CHECK(esp_event_loop_create_default()); + + // Initialize NVS flash for WiFi configuration + esp_err_t ret = nvs_flash_init(); + if (ret == ESP_ERR_NVS_NO_FREE_PAGES || ret == ESP_ERR_NVS_NEW_VERSION_FOUND) { + ESP_LOGW(TAG, "Erasing NVS flash to fix corruption"); + ESP_ERROR_CHECK(nvs_flash_erase()); + ret = nvs_flash_init(); + } + ESP_ERROR_CHECK(ret); + + // Launch the application + auto& app = Application::GetInstance(); + app.Start(); +} diff --git a/main/mcp_server.cc b/main/mcp_server.cc new file mode 100644 index 0000000..949e5d2 --- /dev/null +++ b/main/mcp_server.cc @@ -0,0 +1,565 @@ +/* + * MCP Server Implementation + * Reference: https://modelcontextprotocol.io/specification/2024-11-05 + */ + +#include "mcp_server.h" +#include +#include +#include +#include +#include + +#include "application.h" +#include "display.h" +#include "oled_display.h" +#include "board.h" +#include "settings.h" +#include "lvgl_theme.h" +#include "lvgl_display.h" + +#define TAG "MCP" + +McpServer::McpServer() { +} + +McpServer::~McpServer() { + for (auto tool : tools_) { + delete tool; + } + tools_.clear(); +} + +void McpServer::AddCommonTools() { + // *Important* To speed up the response time, we add the common tools to the beginning of + // the tools list to utilize the prompt cache. + // **重要** 为了提升响应速度,我们把常用的工具放在前面,利用 prompt cache 的特性。 + + // Backup the original tools list and restore it after adding the common tools. + auto original_tools = std::move(tools_); + auto& board = Board::GetInstance(); + + // Do not add custom tools here. + // Custom tools must be added in the board's InitializeTools function. + + AddTool("self.get_device_status", + "Provides the real-time information of the device, including the current status of the audio speaker, screen, battery, network, etc.\n" + "Use this tool for: \n" + "1. Answering questions about current condition (e.g. what is the current volume of the audio speaker?)\n" + "2. As the first step to control the device (e.g. turn up / down the volume of the audio speaker, etc.)", + PropertyList(), + [&board](const PropertyList& properties) -> ReturnValue { + return board.GetDeviceStatusJson(); + }); + + AddTool("self.audio_speaker.set_volume", + "Set the volume of the audio speaker. If the current volume is unknown, you must call `self.get_device_status` tool first and then call this tool.", + PropertyList({ + Property("volume", kPropertyTypeInteger, 0, 100) + }), + [&board](const PropertyList& properties) -> ReturnValue { + auto codec = board.GetAudioCodec(); + codec->SetOutputVolume(properties["volume"].value()); + return true; + }); + + auto backlight = board.GetBacklight(); + if (backlight) { + AddTool("self.screen.set_brightness", + "Set the brightness of the screen.", + PropertyList({ + Property("brightness", kPropertyTypeInteger, 0, 100) + }), + [backlight](const PropertyList& properties) -> ReturnValue { + uint8_t brightness = static_cast(properties["brightness"].value()); + backlight->SetBrightness(brightness, true); + return true; + }); + } + +#ifdef HAVE_LVGL + auto display = board.GetDisplay(); + if (display && display->GetTheme() != nullptr) { + AddTool("self.screen.set_theme", + "Set the theme of the screen. The theme can be `light` or `dark`.", + PropertyList({ + Property("theme", kPropertyTypeString) + }), + [display](const PropertyList& properties) -> ReturnValue { + auto theme_name = properties["theme"].value(); + auto& theme_manager = LvglThemeManager::GetInstance(); + auto theme = theme_manager.GetTheme(theme_name); + if (theme != nullptr) { + display->SetTheme(theme); + return true; + } + return false; + }); + } + + auto camera = board.GetCamera(); + if (camera) { + AddTool("self.camera.take_photo", + "Take a photo and explain it. Use this tool after the user asks you to see something.\n" + "Args:\n" + " `question`: The question that you want to ask about the photo.\n" + "Return:\n" + " A JSON object that provides the photo information.", + PropertyList({ + Property("question", kPropertyTypeString) + }), + [camera](const PropertyList& properties) -> ReturnValue { + // Lower the priority to do the camera capture + TaskPriorityReset priority_reset(1); + + if (!camera->Capture()) { + throw std::runtime_error("Failed to capture photo"); + } + auto question = properties["question"].value(); + return camera->Explain(question); + }); + } +#endif + + // Restore the original tools list to the end of the tools list + tools_.insert(tools_.end(), original_tools.begin(), original_tools.end()); +} + +void McpServer::AddUserOnlyTools() { + // System tools + AddUserOnlyTool("self.get_system_info", + "Get the system information", + PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + auto& board = Board::GetInstance(); + return board.GetSystemInfoJson(); + }); + + AddUserOnlyTool("self.reboot", "Reboot the system", + PropertyList(), + [this](const PropertyList& properties) -> ReturnValue { + auto& app = Application::GetInstance(); + app.Schedule([&app]() { + ESP_LOGW(TAG, "User requested reboot"); + vTaskDelay(pdMS_TO_TICKS(1000)); + + app.Reboot(); + }); + return true; + }); + + // Firmware upgrade + AddUserOnlyTool("self.upgrade_firmware", "Upgrade firmware from a specific URL. This will download and install the firmware, then reboot the device.", + PropertyList({ + Property("url", kPropertyTypeString, "The URL of the firmware binary file to download and install") + }), + [this](const PropertyList& properties) -> ReturnValue { + auto url = properties["url"].value(); + ESP_LOGI(TAG, "User requested firmware upgrade from URL: %s", url.c_str()); + + auto& app = Application::GetInstance(); + app.Schedule([url, &app]() { + auto ota = std::make_unique(); + + bool success = app.UpgradeFirmware(*ota, url); + if (!success) { + ESP_LOGE(TAG, "Firmware upgrade failed"); + } + }); + + return true; + }); + + // Display control +#ifdef HAVE_LVGL + auto display = dynamic_cast(Board::GetInstance().GetDisplay()); + if (display) { + AddUserOnlyTool("self.screen.get_info", "Information about the screen, including width, height, etc.", + PropertyList(), + [display](const PropertyList& properties) -> ReturnValue { + cJSON *json = cJSON_CreateObject(); + cJSON_AddNumberToObject(json, "width", display->width()); + cJSON_AddNumberToObject(json, "height", display->height()); + if (dynamic_cast(display)) { + cJSON_AddBoolToObject(json, "monochrome", true); + } else { + cJSON_AddBoolToObject(json, "monochrome", false); + } + return json; + }); + +#if CONFIG_LV_USE_SNAPSHOT + AddUserOnlyTool("self.screen.snapshot", "Snapshot the screen and upload it to a specific URL", + PropertyList({ + Property("url", kPropertyTypeString), + Property("quality", kPropertyTypeInteger, 80, 1, 100) + }), + [display](const PropertyList& properties) -> ReturnValue { + auto url = properties["url"].value(); + auto quality = properties["quality"].value(); + + std::string jpeg_data; + if (!display->SnapshotToJpeg(jpeg_data, quality)) { + throw std::runtime_error("Failed to snapshot screen"); + } + + ESP_LOGI(TAG, "Upload snapshot %u bytes to %s", jpeg_data.size(), url.c_str()); + + // 构造multipart/form-data请求体 + std::string boundary = "----ESP32_SCREEN_SNAPSHOT_BOUNDARY"; + + auto http = Board::GetInstance().GetNetwork()->CreateHttp(3); + http->SetHeader("Content-Type", "multipart/form-data; boundary=" + boundary); + if (!http->Open("POST", url)) { + throw std::runtime_error("Failed to open URL: " + url); + } + { + // 文件字段头部 + std::string file_header; + file_header += "--" + boundary + "\r\n"; + file_header += "Content-Disposition: form-data; name=\"file\"; filename=\"screenshot.jpg\"\r\n"; + file_header += "Content-Type: image/jpeg\r\n"; + file_header += "\r\n"; + http->Write(file_header.c_str(), file_header.size()); + } + + // JPEG数据 + http->Write((const char*)jpeg_data.data(), jpeg_data.size()); + + { + // multipart尾部 + std::string multipart_footer; + multipart_footer += "\r\n--" + boundary + "--\r\n"; + http->Write(multipart_footer.c_str(), multipart_footer.size()); + } + http->Write("", 0); + + if (http->GetStatusCode() != 200) { + throw std::runtime_error("Unexpected status code: " + std::to_string(http->GetStatusCode())); + } + std::string result = http->ReadAll(); + http->Close(); + ESP_LOGI(TAG, "Snapshot screen result: %s", result.c_str()); + return true; + }); + + AddUserOnlyTool("self.screen.preview_image", "Preview an image on the screen", + PropertyList({ + Property("url", kPropertyTypeString) + }), + [display](const PropertyList& properties) -> ReturnValue { + auto url = properties["url"].value(); + auto http = Board::GetInstance().GetNetwork()->CreateHttp(3); + + if (!http->Open("GET", url)) { + throw std::runtime_error("Failed to open URL: " + url); + } + int status_code = http->GetStatusCode(); + if (status_code != 200) { + throw std::runtime_error("Unexpected status code: " + std::to_string(status_code)); + } + + size_t content_length = http->GetBodyLength(); + char* data = (char*)heap_caps_malloc(content_length, MALLOC_CAP_8BIT); + if (data == nullptr) { + throw std::runtime_error("Failed to allocate memory for image: " + url); + } + size_t total_read = 0; + while (total_read < content_length) { + int ret = http->Read(data + total_read, content_length - total_read); + if (ret < 0) { + heap_caps_free(data); + throw std::runtime_error("Failed to download image: " + url); + } + if (ret == 0) { + break; + } + total_read += ret; + } + http->Close(); + + auto image = std::make_unique(data, content_length); + display->SetPreviewImage(std::move(image)); + return true; + }); +#endif // CONFIG_LV_USE_SNAPSHOT + } +#endif // HAVE_LVGL + + // Assets download url + auto& assets = Assets::GetInstance(); + if (assets.partition_valid()) { + AddUserOnlyTool("self.assets.set_download_url", "Set the download url for the assets", + PropertyList({ + Property("url", kPropertyTypeString) + }), + [](const PropertyList& properties) -> ReturnValue { + auto url = properties["url"].value(); + Settings settings("assets", true); + settings.SetString("download_url", url); + return true; + }); + } +} + +void McpServer::AddTool(McpTool* tool) { + // Prevent adding duplicate tools + if (std::find_if(tools_.begin(), tools_.end(), [tool](const McpTool* t) { return t->name() == tool->name(); }) != tools_.end()) { + ESP_LOGW(TAG, "Tool %s already added", tool->name().c_str()); + return; + } + + ESP_LOGI(TAG, "Add tool: %s%s", tool->name().c_str(), tool->user_only() ? " [user]" : ""); + tools_.push_back(tool); +} + +void McpServer::AddTool(const std::string& name, const std::string& description, const PropertyList& properties, std::function callback) { + AddTool(new McpTool(name, description, properties, callback)); +} + +void McpServer::AddUserOnlyTool(const std::string& name, const std::string& description, const PropertyList& properties, std::function callback) { + auto tool = new McpTool(name, description, properties, callback); + tool->set_user_only(true); + AddTool(tool); +} + +void McpServer::ParseMessage(const std::string& message) { + cJSON* json = cJSON_Parse(message.c_str()); + if (json == nullptr) { + ESP_LOGE(TAG, "Failed to parse MCP message: %s", message.c_str()); + return; + } + ParseMessage(json); + cJSON_Delete(json); +} + +void McpServer::ParseCapabilities(const cJSON* capabilities) { + auto vision = cJSON_GetObjectItem(capabilities, "vision"); + if (cJSON_IsObject(vision)) { + auto url = cJSON_GetObjectItem(vision, "url"); + auto token = cJSON_GetObjectItem(vision, "token"); + if (cJSON_IsString(url)) { + auto camera = Board::GetInstance().GetCamera(); + if (camera) { + std::string url_str = std::string(url->valuestring); + std::string token_str; + if (cJSON_IsString(token)) { + token_str = std::string(token->valuestring); + } + camera->SetExplainUrl(url_str, token_str); + } + } + } +} + +void McpServer::ParseMessage(const cJSON* json) { + // Check JSONRPC version + auto version = cJSON_GetObjectItem(json, "jsonrpc"); + if (version == nullptr || !cJSON_IsString(version) || strcmp(version->valuestring, "2.0") != 0) { + ESP_LOGE(TAG, "Invalid JSONRPC version: %s", version ? version->valuestring : "null"); + return; + } + + // Check method + auto method = cJSON_GetObjectItem(json, "method"); + if (method == nullptr || !cJSON_IsString(method)) { + ESP_LOGE(TAG, "Missing method"); + return; + } + + auto method_str = std::string(method->valuestring); + if (method_str.find("notifications") == 0) { + return; + } + + // Check params + auto params = cJSON_GetObjectItem(json, "params"); + if (params != nullptr && !cJSON_IsObject(params)) { + ESP_LOGE(TAG, "Invalid params for method: %s", method_str.c_str()); + return; + } + + auto id = cJSON_GetObjectItem(json, "id"); + if (id == nullptr || !cJSON_IsNumber(id)) { + ESP_LOGE(TAG, "Invalid id for method: %s", method_str.c_str()); + return; + } + auto id_int = id->valueint; + + if (method_str == "initialize") { + if (cJSON_IsObject(params)) { + auto capabilities = cJSON_GetObjectItem(params, "capabilities"); + if (cJSON_IsObject(capabilities)) { + ParseCapabilities(capabilities); + } + } + auto app_desc = esp_app_get_description(); + std::string message = "{\"protocolVersion\":\"2024-11-05\",\"capabilities\":{\"tools\":{}},\"serverInfo\":{\"name\":\"" BOARD_NAME "\",\"version\":\""; + message += app_desc->version; + message += "\"}}"; + ReplyResult(id_int, message); + } else if (method_str == "tools/list") { + std::string cursor_str = ""; + bool list_user_only_tools = false; + if (params != nullptr) { + auto cursor = cJSON_GetObjectItem(params, "cursor"); + if (cJSON_IsString(cursor)) { + cursor_str = std::string(cursor->valuestring); + } + auto with_user_tools = cJSON_GetObjectItem(params, "withUserTools"); + if (cJSON_IsBool(with_user_tools)) { + list_user_only_tools = with_user_tools->valueint == 1; + } + } + GetToolsList(id_int, cursor_str, list_user_only_tools); + } else if (method_str == "tools/call") { + if (!cJSON_IsObject(params)) { + ESP_LOGE(TAG, "tools/call: Missing params"); + ReplyError(id_int, "Missing params"); + return; + } + auto tool_name = cJSON_GetObjectItem(params, "name"); + if (!cJSON_IsString(tool_name)) { + ESP_LOGE(TAG, "tools/call: Missing name"); + ReplyError(id_int, "Missing name"); + return; + } + auto tool_arguments = cJSON_GetObjectItem(params, "arguments"); + if (tool_arguments != nullptr && !cJSON_IsObject(tool_arguments)) { + ESP_LOGE(TAG, "tools/call: Invalid arguments"); + ReplyError(id_int, "Invalid arguments"); + return; + } + DoToolCall(id_int, std::string(tool_name->valuestring), tool_arguments); + } else { + ESP_LOGE(TAG, "Method not implemented: %s", method_str.c_str()); + ReplyError(id_int, "Method not implemented: " + method_str); + } +} + +void McpServer::ReplyResult(int id, const std::string& result) { + std::string payload = "{\"jsonrpc\":\"2.0\",\"id\":"; + payload += std::to_string(id) + ",\"result\":"; + payload += result; + payload += "}"; + Application::GetInstance().SendMcpMessage(payload); +} + +void McpServer::ReplyError(int id, const std::string& message) { + std::string payload = "{\"jsonrpc\":\"2.0\",\"id\":"; + payload += std::to_string(id); + payload += ",\"error\":{\"message\":\""; + payload += message; + payload += "\"}}"; + Application::GetInstance().SendMcpMessage(payload); +} + +void McpServer::GetToolsList(int id, const std::string& cursor, bool list_user_only_tools) { + const int max_payload_size = 8000; + std::string json = "{\"tools\":["; + + bool found_cursor = cursor.empty(); + auto it = tools_.begin(); + std::string next_cursor = ""; + + while (it != tools_.end()) { + // 如果我们还没有找到起始位置,继续搜索 + if (!found_cursor) { + if ((*it)->name() == cursor) { + found_cursor = true; + } else { + ++it; + continue; + } + } + + if (!list_user_only_tools && (*it)->user_only()) { + ++it; + continue; + } + + // 添加tool前检查大小 + std::string tool_json = (*it)->to_json() + ","; + if (json.length() + tool_json.length() + 30 > max_payload_size) { + // 如果添加这个tool会超出大小限制,设置next_cursor并退出循环 + next_cursor = (*it)->name(); + break; + } + + json += tool_json; + ++it; + } + + if (json.back() == ',') { + json.pop_back(); + } + + if (json.back() == '[' && !tools_.empty()) { + // 如果没有添加任何tool,返回错误 + ESP_LOGE(TAG, "tools/list: Failed to add tool %s because of payload size limit", next_cursor.c_str()); + ReplyError(id, "Failed to add tool " + next_cursor + " because of payload size limit"); + return; + } + + if (next_cursor.empty()) { + json += "]}"; + } else { + json += "],\"nextCursor\":\"" + next_cursor + "\"}"; + } + + ReplyResult(id, json); +} + +void McpServer::DoToolCall(int id, const std::string& tool_name, const cJSON* tool_arguments) { + auto tool_iter = std::find_if(tools_.begin(), tools_.end(), + [&tool_name](const McpTool* tool) { + return tool->name() == tool_name; + }); + + if (tool_iter == tools_.end()) { + ESP_LOGE(TAG, "tools/call: Unknown tool: %s", tool_name.c_str()); + ReplyError(id, "Unknown tool: " + tool_name); + return; + } + + PropertyList arguments = (*tool_iter)->properties(); + try { + for (auto& argument : arguments) { + bool found = false; + if (cJSON_IsObject(tool_arguments)) { + auto value = cJSON_GetObjectItem(tool_arguments, argument.name().c_str()); + if (argument.type() == kPropertyTypeBoolean && cJSON_IsBool(value)) { + argument.set_value(value->valueint == 1); + found = true; + } else if (argument.type() == kPropertyTypeInteger && cJSON_IsNumber(value)) { + argument.set_value(value->valueint); + found = true; + } else if (argument.type() == kPropertyTypeString && cJSON_IsString(value)) { + argument.set_value(value->valuestring); + found = true; + } + } + + if (!argument.has_default_value() && !found) { + ESP_LOGE(TAG, "tools/call: Missing valid argument: %s", argument.name().c_str()); + ReplyError(id, "Missing valid argument: " + argument.name()); + return; + } + } + } catch (const std::exception& e) { + ESP_LOGE(TAG, "tools/call: %s", e.what()); + ReplyError(id, e.what()); + return; + } + + // Use main thread to call the tool + auto& app = Application::GetInstance(); + app.Schedule([this, id, tool_iter, arguments = std::move(arguments)]() { + try { + ReplyResult(id, (*tool_iter)->Call(arguments)); + } catch (const std::exception& e) { + ESP_LOGE(TAG, "tools/call: %s", e.what()); + ReplyError(id, e.what()); + } + }); +} diff --git a/main/mcp_server.h b/main/mcp_server.h new file mode 100644 index 0000000..dacdd55 --- /dev/null +++ b/main/mcp_server.h @@ -0,0 +1,344 @@ +#ifndef MCP_SERVER_H +#define MCP_SERVER_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +class ImageContent { +private: + std::string encoded_data_; + std::string mime_type_; + + static std::string Base64Encode(const std::string& data) { + size_t dlen = 0, olen = 0; + mbedtls_base64_encode((unsigned char*)nullptr, 0, &dlen, (const unsigned char*)data.data(), data.size()); + std::string result(dlen, 0); + mbedtls_base64_encode((unsigned char*)result.data(), result.size(), &olen, (const unsigned char*)data.data(), data.size()); + return result; + } + +public: + ImageContent(const std::string& mime_type, const std::string& data) { + mime_type_ = mime_type; + // base64 encode data + encoded_data_ = Base64Encode(data); + } + + std::string to_json() const { + cJSON *json = cJSON_CreateObject(); + cJSON_AddStringToObject(json, "type", "image"); + cJSON_AddStringToObject(json, "mimeType", mime_type_.c_str()); + cJSON_AddStringToObject(json, "data", encoded_data_.c_str()); + char* json_str = cJSON_PrintUnformatted(json); + std::string result(json_str); + cJSON_free(json_str); + cJSON_Delete(json); + return result; + } +}; + +// 添加类型别名 +using ReturnValue = std::variant; + +enum PropertyType { + kPropertyTypeBoolean, + kPropertyTypeInteger, + kPropertyTypeString +}; + +class Property { +private: + std::string name_; + PropertyType type_; + std::variant value_; + bool has_default_value_; + std::optional min_value_; // 新增:整数最小值 + std::optional max_value_; // 新增:整数最大值 + +public: + // Required field constructor + Property(const std::string& name, PropertyType type) + : name_(name), type_(type), has_default_value_(false) {} + + // Optional field constructor with default value + template + Property(const std::string& name, PropertyType type, const T& default_value) + : name_(name), type_(type), has_default_value_(true) { + value_ = default_value; + } + + Property(const std::string& name, PropertyType type, int min_value, int max_value) + : name_(name), type_(type), has_default_value_(false), min_value_(min_value), max_value_(max_value) { + if (type != kPropertyTypeInteger) { + throw std::invalid_argument("Range limits only apply to integer properties"); + } + } + + Property(const std::string& name, PropertyType type, int default_value, int min_value, int max_value) + : name_(name), type_(type), has_default_value_(true), min_value_(min_value), max_value_(max_value) { + if (type != kPropertyTypeInteger) { + throw std::invalid_argument("Range limits only apply to integer properties"); + } + if (default_value < min_value || default_value > max_value) { + throw std::invalid_argument("Default value must be within the specified range"); + } + value_ = default_value; + } + + inline const std::string& name() const { return name_; } + inline PropertyType type() const { return type_; } + inline bool has_default_value() const { return has_default_value_; } + inline bool has_range() const { return min_value_.has_value() && max_value_.has_value(); } + inline int min_value() const { return min_value_.value_or(0); } + inline int max_value() const { return max_value_.value_or(0); } + + template + inline T value() const { + return std::get(value_); + } + + template + inline void set_value(const T& value) { + // 添加对设置的整数值进行范围检查 + if constexpr (std::is_same_v) { + if (min_value_.has_value() && value < min_value_.value()) { + throw std::invalid_argument("Value is below minimum allowed: " + std::to_string(min_value_.value())); + } + if (max_value_.has_value() && value > max_value_.value()) { + throw std::invalid_argument("Value exceeds maximum allowed: " + std::to_string(max_value_.value())); + } + } + value_ = value; + } + + std::string to_json() const { + cJSON *json = cJSON_CreateObject(); + + if (type_ == kPropertyTypeBoolean) { + cJSON_AddStringToObject(json, "type", "boolean"); + if (has_default_value_) { + cJSON_AddBoolToObject(json, "default", value()); + } + } else if (type_ == kPropertyTypeInteger) { + cJSON_AddStringToObject(json, "type", "integer"); + if (has_default_value_) { + cJSON_AddNumberToObject(json, "default", value()); + } + if (min_value_.has_value()) { + cJSON_AddNumberToObject(json, "minimum", min_value_.value()); + } + if (max_value_.has_value()) { + cJSON_AddNumberToObject(json, "maximum", max_value_.value()); + } + } else if (type_ == kPropertyTypeString) { + cJSON_AddStringToObject(json, "type", "string"); + if (has_default_value_) { + cJSON_AddStringToObject(json, "default", value().c_str()); + } + } + + char *json_str = cJSON_PrintUnformatted(json); + std::string result(json_str); + cJSON_free(json_str); + cJSON_Delete(json); + + return result; + } +}; + +class PropertyList { +private: + std::vector properties_; + +public: + PropertyList() = default; + PropertyList(const std::vector& properties) : properties_(properties) {} + void AddProperty(const Property& property) { + properties_.push_back(property); + } + + const Property& operator[](const std::string& name) const { + for (const auto& property : properties_) { + if (property.name() == name) { + return property; + } + } + throw std::runtime_error("Property not found: " + name); + } + + auto begin() { return properties_.begin(); } + auto end() { return properties_.end(); } + + std::vector GetRequired() const { + std::vector required; + for (auto& property : properties_) { + if (!property.has_default_value()) { + required.push_back(property.name()); + } + } + return required; + } + + std::string to_json() const { + cJSON *json = cJSON_CreateObject(); + + for (const auto& property : properties_) { + cJSON *prop_json = cJSON_Parse(property.to_json().c_str()); + cJSON_AddItemToObject(json, property.name().c_str(), prop_json); + } + + char *json_str = cJSON_PrintUnformatted(json); + std::string result(json_str); + cJSON_free(json_str); + cJSON_Delete(json); + + return result; + } +}; + +class McpTool { +private: + std::string name_; + std::string description_; + PropertyList properties_; + std::function callback_; + bool user_only_ = false; + +public: + McpTool(const std::string& name, + const std::string& description, + const PropertyList& properties, + std::function callback) + : name_(name), + description_(description), + properties_(properties), + callback_(callback) {} + + void set_user_only(bool user_only) { user_only_ = user_only; } + inline const std::string& name() const { return name_; } + inline const std::string& description() const { return description_; } + inline const PropertyList& properties() const { return properties_; } + inline bool user_only() const { return user_only_; } + + std::string to_json() const { + std::vector required = properties_.GetRequired(); + + cJSON *json = cJSON_CreateObject(); + cJSON_AddStringToObject(json, "name", name_.c_str()); + cJSON_AddStringToObject(json, "description", description_.c_str()); + + cJSON *input_schema = cJSON_CreateObject(); + cJSON_AddStringToObject(input_schema, "type", "object"); + + cJSON *properties = cJSON_Parse(properties_.to_json().c_str()); + cJSON_AddItemToObject(input_schema, "properties", properties); + + if (!required.empty()) { + cJSON *required_array = cJSON_CreateArray(); + for (const auto& property : required) { + cJSON_AddItemToArray(required_array, cJSON_CreateString(property.c_str())); + } + cJSON_AddItemToObject(input_schema, "required", required_array); + } + + cJSON_AddItemToObject(json, "inputSchema", input_schema); + + // Add audience annotation if the tool is user only (invisible to AI) + if (user_only_) { + cJSON *annotations = cJSON_CreateObject(); + cJSON *audience = cJSON_CreateArray(); + cJSON_AddItemToArray(audience, cJSON_CreateString("user")); + cJSON_AddItemToObject(annotations, "audience", audience); + cJSON_AddItemToObject(json, "annotations", annotations); + } + + char *json_str = cJSON_PrintUnformatted(json); + std::string result(json_str); + cJSON_free(json_str); + cJSON_Delete(json); + + return result; + } + + std::string Call(const PropertyList& properties) { + ReturnValue return_value = callback_(properties); + // 返回结果 + cJSON* result = cJSON_CreateObject(); + cJSON* content = cJSON_CreateArray(); + + if (std::holds_alternative(return_value)) { + auto image_content = std::get(return_value); + cJSON* image = cJSON_CreateObject(); + cJSON_AddStringToObject(image, "type", "image"); + cJSON_AddStringToObject(image, "image", image_content->to_json().c_str()); + cJSON_AddItemToArray(content, image); + delete image_content; + } else { + cJSON* text = cJSON_CreateObject(); + cJSON_AddStringToObject(text, "type", "text"); + if (std::holds_alternative(return_value)) { + cJSON_AddStringToObject(text, "text", std::get(return_value).c_str()); + } else if (std::holds_alternative(return_value)) { + cJSON_AddStringToObject(text, "text", std::get(return_value) ? "true" : "false"); + } else if (std::holds_alternative(return_value)) { + cJSON_AddStringToObject(text, "text", std::to_string(std::get(return_value)).c_str()); + } else if (std::holds_alternative(return_value)) { + cJSON* json = std::get(return_value); + char* json_str = cJSON_PrintUnformatted(json); + cJSON_AddStringToObject(text, "text", json_str); + cJSON_free(json_str); + cJSON_Delete(json); + } + cJSON_AddItemToArray(content, text); + } + cJSON_AddItemToObject(result, "content", content); + cJSON_AddBoolToObject(result, "isError", false); + + auto json_str = cJSON_PrintUnformatted(result); + std::string result_str(json_str); + cJSON_free(json_str); + cJSON_Delete(result); + return result_str; + } +}; + +class McpServer { +public: + static McpServer& GetInstance() { + static McpServer instance; + return instance; + } + + void AddCommonTools(); + void AddUserOnlyTools(); + void AddTool(McpTool* tool); + void AddTool(const std::string& name, const std::string& description, const PropertyList& properties, std::function callback); + void AddUserOnlyTool(const std::string& name, const std::string& description, const PropertyList& properties, std::function callback); + void ParseMessage(const cJSON* json); + void ParseMessage(const std::string& message); + +private: + McpServer(); + ~McpServer(); + + void ParseCapabilities(const cJSON* capabilities); + + void ReplyResult(int id, const std::string& result); + void ReplyError(int id, const std::string& message); + + void GetToolsList(int id, const std::string& cursor, bool list_user_only_tools); + void DoToolCall(int id, const std::string& tool_name, const cJSON* tool_arguments); + + std::vector tools_; +}; + +#endif // MCP_SERVER_H diff --git a/main/ota.cc b/main/ota.cc new file mode 100644 index 0000000..0f3e29c --- /dev/null +++ b/main/ota.cc @@ -0,0 +1,478 @@ +#include "ota.h" +#include "system_info.h" +#include "settings.h" +#include "assets/lang_config.h" + +#include +#include +#include +#include +#include +#include +#include +#ifdef SOC_HMAC_SUPPORTED +#include +#endif + +#include +#include +#include +#include + +#define TAG "Ota" + + +Ota::Ota() { +#ifdef ESP_EFUSE_BLOCK_USR_DATA + // Read Serial Number from efuse user_data + uint8_t serial_number[33] = {0}; + if (esp_efuse_read_field_blob(ESP_EFUSE_USER_DATA, serial_number, 32 * 8) == ESP_OK) { + if (serial_number[0] == 0) { + has_serial_number_ = false; + } else { + serial_number_ = std::string(reinterpret_cast(serial_number), 32); + has_serial_number_ = true; + } + } +#endif +} + +Ota::~Ota() { +} + +std::string Ota::GetCheckVersionUrl() { + Settings settings("wifi", false); + std::string url = settings.GetString("ota_url"); + if (url.empty()) { + url = CONFIG_OTA_URL; + } + return url; +} + +std::unique_ptr Ota::SetupHttp() { + auto& board = Board::GetInstance(); + auto network = board.GetNetwork(); + auto http = network->CreateHttp(0); + auto user_agent = SystemInfo::GetUserAgent(); + http->SetHeader("Activation-Version", has_serial_number_ ? "2" : "1"); + http->SetHeader("Device-Id", SystemInfo::GetMacAddress().c_str()); + http->SetHeader("Client-Id", board.GetUuid()); + if (has_serial_number_) { + http->SetHeader("Serial-Number", serial_number_.c_str()); + ESP_LOGI(TAG, "Setup HTTP, User-Agent: %s, Serial-Number: %s", user_agent.c_str(), serial_number_.c_str()); + } + http->SetHeader("User-Agent", user_agent); + http->SetHeader("Accept-Language", Lang::CODE); + http->SetHeader("Content-Type", "application/json"); + + return http; +} + +/* + * Specification: https://ccnphfhqs21z.feishu.cn/wiki/FjW6wZmisimNBBkov6OcmfvknVd + */ +esp_err_t Ota::CheckVersion() { + auto& board = Board::GetInstance(); + auto app_desc = esp_app_get_description(); + + // Check if there is a new firmware version available + current_version_ = app_desc->version; + ESP_LOGI(TAG, "Current version: %s", current_version_.c_str()); + + std::string url = GetCheckVersionUrl(); + if (url.length() < 10) { + ESP_LOGE(TAG, "Check version URL is not properly set"); + return ESP_ERR_INVALID_ARG; + } + + auto http = SetupHttp(); + + std::string data = board.GetSystemInfoJson(); + std::string method = data.length() > 0 ? "POST" : "GET"; + http->SetContent(std::move(data)); + + if (!http->Open(method, url)) { + int last_error = http->GetLastError(); + ESP_LOGE(TAG, "Failed to open HTTP connection, code=0x%x", last_error); + return last_error; + } + + auto status_code = http->GetStatusCode(); + if (status_code != 200) { + ESP_LOGE(TAG, "Failed to check version, status code: %d", status_code); + return status_code; + } + + data = http->ReadAll(); + http->Close(); + + // Response: { "firmware": { "version": "1.0.0", "url": "http://" } } + // Parse the JSON response and check if the version is newer + // If it is, set has_new_version_ to true and store the new version and URL + + cJSON *root = cJSON_Parse(data.c_str()); + if (root == NULL) { + ESP_LOGE(TAG, "Failed to parse JSON response"); + return ESP_ERR_INVALID_RESPONSE; + } + + has_activation_code_ = false; + has_activation_challenge_ = false; + cJSON *activation = cJSON_GetObjectItem(root, "activation"); + if (cJSON_IsObject(activation)) { + cJSON* message = cJSON_GetObjectItem(activation, "message"); + if (cJSON_IsString(message)) { + activation_message_ = message->valuestring; + } + cJSON* code = cJSON_GetObjectItem(activation, "code"); + if (cJSON_IsString(code)) { + activation_code_ = code->valuestring; + has_activation_code_ = true; + } + cJSON* challenge = cJSON_GetObjectItem(activation, "challenge"); + if (cJSON_IsString(challenge)) { + activation_challenge_ = challenge->valuestring; + has_activation_challenge_ = true; + } + cJSON* timeout_ms = cJSON_GetObjectItem(activation, "timeout_ms"); + if (cJSON_IsNumber(timeout_ms)) { + activation_timeout_ms_ = timeout_ms->valueint; + } + } + + has_mqtt_config_ = false; + cJSON *mqtt = cJSON_GetObjectItem(root, "mqtt"); + if (cJSON_IsObject(mqtt)) { + Settings settings("mqtt", true); + cJSON *item = NULL; + cJSON_ArrayForEach(item, mqtt) { + if (cJSON_IsString(item)) { + if (settings.GetString(item->string) != item->valuestring) { + settings.SetString(item->string, item->valuestring); + } + } else if (cJSON_IsNumber(item)) { + if (settings.GetInt(item->string) != item->valueint) { + settings.SetInt(item->string, item->valueint); + } + } + } + has_mqtt_config_ = true; + } else { + ESP_LOGI(TAG, "No mqtt section found !"); + } + + has_websocket_config_ = false; + cJSON *websocket = cJSON_GetObjectItem(root, "websocket"); + if (cJSON_IsObject(websocket)) { + Settings settings("websocket", true); + cJSON *item = NULL; + cJSON_ArrayForEach(item, websocket) { + if (cJSON_IsString(item)) { + if (settings.GetString(item->string) != item->valuestring) { + settings.SetString(item->string, item->valuestring); + } + } else if (cJSON_IsNumber(item)) { + if (settings.GetInt(item->string) != item->valueint) { + settings.SetInt(item->string, item->valueint); + } + } + } + has_websocket_config_ = true; + } else { + ESP_LOGI(TAG, "No websocket section found!"); + } + + has_server_time_ = false; + cJSON *server_time = cJSON_GetObjectItem(root, "server_time"); + if (cJSON_IsObject(server_time)) { + cJSON *timestamp = cJSON_GetObjectItem(server_time, "timestamp"); + cJSON *timezone_offset = cJSON_GetObjectItem(server_time, "timezone_offset"); + + if (cJSON_IsNumber(timestamp)) { + // 设置系统时间 + struct timeval tv; + double ts = timestamp->valuedouble; + + // 如果有时区偏移,计算本地时间 + if (cJSON_IsNumber(timezone_offset)) { + ts += (timezone_offset->valueint * 60 * 1000); // 转换分钟为毫秒 + } + + tv.tv_sec = (time_t)(ts / 1000); // 转换毫秒为秒 + tv.tv_usec = (suseconds_t)((long long)ts % 1000) * 1000; // 剩余的毫秒转换为微秒 + settimeofday(&tv, NULL); + has_server_time_ = true; + } + } else { + ESP_LOGW(TAG, "No server_time section found!"); + } + + has_new_version_ = false; + cJSON *firmware = cJSON_GetObjectItem(root, "firmware"); + if (cJSON_IsObject(firmware)) { + cJSON *version = cJSON_GetObjectItem(firmware, "version"); + if (cJSON_IsString(version)) { + firmware_version_ = version->valuestring; + } + cJSON *url = cJSON_GetObjectItem(firmware, "url"); + if (cJSON_IsString(url)) { + firmware_url_ = url->valuestring; + } + + if (cJSON_IsString(version) && cJSON_IsString(url)) { + // Check if the version is newer, for example, 0.1.0 is newer than 0.0.1 + has_new_version_ = IsNewVersionAvailable(current_version_, firmware_version_); + if (has_new_version_) { + ESP_LOGI(TAG, "New version available: %s", firmware_version_.c_str()); + } else { + ESP_LOGI(TAG, "Current is the latest version"); + } + // If the force flag is set to 1, the given version is forced to be installed + cJSON *force = cJSON_GetObjectItem(firmware, "force"); + if (cJSON_IsNumber(force) && force->valueint == 1) { + has_new_version_ = true; + } + } + } else { + ESP_LOGW(TAG, "No firmware section found!"); + } + + cJSON_Delete(root); + return ESP_OK; +} + +void Ota::MarkCurrentVersionValid() { + auto partition = esp_ota_get_running_partition(); + if (strcmp(partition->label, "factory") == 0) { + ESP_LOGI(TAG, "Running from factory partition, skipping"); + return; + } + + ESP_LOGI(TAG, "Running partition: %s", partition->label); + esp_ota_img_states_t state; + if (esp_ota_get_state_partition(partition, &state) != ESP_OK) { + ESP_LOGE(TAG, "Failed to get state of partition"); + return; + } + + if (state == ESP_OTA_IMG_PENDING_VERIFY) { + ESP_LOGI(TAG, "Marking firmware as valid"); + esp_ota_mark_app_valid_cancel_rollback(); + } +} + +bool Ota::Upgrade(const std::string& firmware_url) { + ESP_LOGI(TAG, "Upgrading firmware from %s", firmware_url.c_str()); + esp_ota_handle_t update_handle = 0; + auto update_partition = esp_ota_get_next_update_partition(NULL); + if (update_partition == NULL) { + ESP_LOGE(TAG, "Failed to get update partition"); + return false; + } + + ESP_LOGI(TAG, "Writing to partition %s at offset 0x%lx", update_partition->label, update_partition->address); + bool image_header_checked = false; + std::string image_header; + + auto network = Board::GetInstance().GetNetwork(); + auto http = network->CreateHttp(0); + if (!http->Open("GET", firmware_url)) { + ESP_LOGE(TAG, "Failed to open HTTP connection"); + return false; + } + + if (http->GetStatusCode() != 200) { + ESP_LOGE(TAG, "Failed to get firmware, status code: %d", http->GetStatusCode()); + return false; + } + + size_t content_length = http->GetBodyLength(); + if (content_length == 0) { + ESP_LOGE(TAG, "Failed to get content length"); + return false; + } + + char buffer[512]; + size_t total_read = 0, recent_read = 0; + auto last_calc_time = esp_timer_get_time(); + while (true) { + int ret = http->Read(buffer, sizeof(buffer)); + if (ret < 0) { + ESP_LOGE(TAG, "Failed to read HTTP data: %s", esp_err_to_name(ret)); + return false; + } + + // Calculate speed and progress every second + recent_read += ret; + total_read += ret; + if (esp_timer_get_time() - last_calc_time >= 1000000 || ret == 0) { + size_t progress = total_read * 100 / content_length; + ESP_LOGI(TAG, "Progress: %u%% (%u/%u), Speed: %uB/s", progress, total_read, content_length, recent_read); + if (upgrade_callback_) { + upgrade_callback_(progress, recent_read); + } + last_calc_time = esp_timer_get_time(); + recent_read = 0; + } + + if (ret == 0) { + break; + } + + if (!image_header_checked) { + image_header.append(buffer, ret); + if (image_header.size() >= sizeof(esp_image_header_t) + sizeof(esp_image_segment_header_t) + sizeof(esp_app_desc_t)) { + esp_app_desc_t new_app_info; + memcpy(&new_app_info, image_header.data() + sizeof(esp_image_header_t) + sizeof(esp_image_segment_header_t), sizeof(esp_app_desc_t)); + + auto current_version = esp_app_get_description()->version; + ESP_LOGI(TAG, "Current version: %s, New version: %s", current_version, new_app_info.version); + + if (esp_ota_begin(update_partition, OTA_WITH_SEQUENTIAL_WRITES, &update_handle)) { + esp_ota_abort(update_handle); + ESP_LOGE(TAG, "Failed to begin OTA"); + return false; + } + + image_header_checked = true; + std::string().swap(image_header); + } + } + auto err = esp_ota_write(update_handle, buffer, ret); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to write OTA data: %s", esp_err_to_name(err)); + esp_ota_abort(update_handle); + return false; + } + } + http->Close(); + + esp_err_t err = esp_ota_end(update_handle); + if (err != ESP_OK) { + if (err == ESP_ERR_OTA_VALIDATE_FAILED) { + ESP_LOGE(TAG, "Image validation failed, image is corrupted"); + } else { + ESP_LOGE(TAG, "Failed to end OTA: %s", esp_err_to_name(err)); + } + return false; + } + + err = esp_ota_set_boot_partition(update_partition); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Failed to set boot partition: %s", esp_err_to_name(err)); + return false; + } + + ESP_LOGI(TAG, "Firmware upgrade successful"); + return true; +} + +bool Ota::StartUpgrade(std::function callback) { + upgrade_callback_ = callback; + return Upgrade(firmware_url_); +} + +bool Ota::StartUpgradeFromUrl(const std::string& url, std::function callback) { + upgrade_callback_ = callback; + return Upgrade(url); +} + +std::vector Ota::ParseVersion(const std::string& version) { + std::vector versionNumbers; + std::stringstream ss(version); + std::string segment; + + while (std::getline(ss, segment, '.')) { + versionNumbers.push_back(std::stoi(segment)); + } + + return versionNumbers; +} + +bool Ota::IsNewVersionAvailable(const std::string& currentVersion, const std::string& newVersion) { + std::vector current = ParseVersion(currentVersion); + std::vector newer = ParseVersion(newVersion); + + for (size_t i = 0; i < std::min(current.size(), newer.size()); ++i) { + if (newer[i] > current[i]) { + return true; + } else if (newer[i] < current[i]) { + return false; + } + } + + return newer.size() > current.size(); +} + +std::string Ota::GetActivationPayload() { + if (!has_serial_number_) { + return "{}"; + } + + std::string hmac_hex; +#ifdef SOC_HMAC_SUPPORTED + uint8_t hmac_result[32]; // SHA-256 输出为32字节 + + // 使用Key0计算HMAC + esp_err_t ret = esp_hmac_calculate(HMAC_KEY0, (uint8_t*)activation_challenge_.data(), activation_challenge_.size(), hmac_result); + if (ret != ESP_OK) { + ESP_LOGE(TAG, "HMAC calculation failed: %s", esp_err_to_name(ret)); + return "{}"; + } + + for (size_t i = 0; i < sizeof(hmac_result); i++) { + char buffer[3]; + sprintf(buffer, "%02x", hmac_result[i]); + hmac_hex += buffer; + } +#endif + + cJSON *payload = cJSON_CreateObject(); + cJSON_AddStringToObject(payload, "algorithm", "hmac-sha256"); + cJSON_AddStringToObject(payload, "serial_number", serial_number_.c_str()); + cJSON_AddStringToObject(payload, "challenge", activation_challenge_.c_str()); + cJSON_AddStringToObject(payload, "hmac", hmac_hex.c_str()); + auto json_str = cJSON_PrintUnformatted(payload); + std::string json(json_str); + cJSON_free(json_str); + cJSON_Delete(payload); + + ESP_LOGI(TAG, "Activation payload: %s", json.c_str()); + return json; +} + +esp_err_t Ota::Activate() { + if (!has_activation_challenge_) { + ESP_LOGW(TAG, "No activation challenge found"); + return ESP_FAIL; + } + + std::string url = GetCheckVersionUrl(); + if (url.back() != '/') { + url += "/activate"; + } else { + url += "activate"; + } + + auto http = SetupHttp(); + + std::string data = GetActivationPayload(); + http->SetContent(std::move(data)); + + if (!http->Open("POST", url)) { + ESP_LOGE(TAG, "Failed to open HTTP connection"); + return ESP_FAIL; + } + + auto status_code = http->GetStatusCode(); + if (status_code == 202) { + return ESP_ERR_TIMEOUT; + } + if (status_code != 200) { + ESP_LOGE(TAG, "Failed to activate, code: %d, body: %s", status_code, http->ReadAll().c_str()); + return ESP_FAIL; + } + + ESP_LOGI(TAG, "Activation successful"); + return ESP_OK; +} diff --git a/main/ota.h b/main/ota.h new file mode 100644 index 0000000..4564920 --- /dev/null +++ b/main/ota.h @@ -0,0 +1,59 @@ +#ifndef _OTA_H +#define _OTA_H + +#include +#include + +#include +#include "board.h" + +class Ota { +public: + Ota(); + ~Ota(); + + esp_err_t CheckVersion(); + esp_err_t Activate(); + bool HasActivationChallenge() { return has_activation_challenge_; } + bool HasNewVersion() { return has_new_version_; } + bool HasMqttConfig() { return has_mqtt_config_; } + bool HasWebsocketConfig() { return has_websocket_config_; } + bool HasActivationCode() { return has_activation_code_; } + bool HasServerTime() { return has_server_time_; } + bool StartUpgrade(std::function callback); + bool StartUpgradeFromUrl(const std::string& url, std::function callback); + void MarkCurrentVersionValid(); + + const std::string& GetFirmwareVersion() const { return firmware_version_; } + const std::string& GetCurrentVersion() const { return current_version_; } + const std::string& GetFirmwareUrl() const { return firmware_url_; } + const std::string& GetActivationMessage() const { return activation_message_; } + const std::string& GetActivationCode() const { return activation_code_; } + std::string GetCheckVersionUrl(); + +private: + std::string activation_message_; + std::string activation_code_; + bool has_new_version_ = false; + bool has_mqtt_config_ = false; + bool has_websocket_config_ = false; + bool has_server_time_ = false; + bool has_activation_code_ = false; + bool has_serial_number_ = false; + bool has_activation_challenge_ = false; + std::string current_version_; + std::string firmware_version_; + std::string firmware_url_; + std::string activation_challenge_; + std::string serial_number_; + int activation_timeout_ms_ = 30000; + + bool Upgrade(const std::string& firmware_url); + std::function upgrade_callback_; + std::vector ParseVersion(const std::string& version); + bool IsNewVersionAvailable(const std::string& currentVersion, const std::string& newVersion); + std::string GetActivationPayload(); + std::unique_ptr SetupHttp(); +}; + +#endif // _OTA_H diff --git a/main/protocols/mqtt_protocol.cc b/main/protocols/mqtt_protocol.cc new file mode 100644 index 0000000..3c8fc8d --- /dev/null +++ b/main/protocols/mqtt_protocol.cc @@ -0,0 +1,372 @@ +#include "mqtt_protocol.h" +#include "board.h" +#include "application.h" +#include "settings.h" + +#include +#include +#include +#include "assets/lang_config.h" + +#define TAG "MQTT" + +MqttProtocol::MqttProtocol() { + event_group_handle_ = xEventGroupCreate(); + + // Initialize reconnect timer + esp_timer_create_args_t reconnect_timer_args = { + .callback = [](void* arg) { + MqttProtocol* protocol = (MqttProtocol*)arg; + auto& app = Application::GetInstance(); + if (app.GetDeviceState() == kDeviceStateIdle) { + ESP_LOGI(TAG, "Reconnecting to MQTT server"); + app.Schedule([protocol]() { + protocol->StartMqttClient(false); + }); + } + }, + .arg = this, + }; + esp_timer_create(&reconnect_timer_args, &reconnect_timer_); +} + +MqttProtocol::~MqttProtocol() { + ESP_LOGI(TAG, "MqttProtocol deinit"); + if (reconnect_timer_ != nullptr) { + esp_timer_stop(reconnect_timer_); + esp_timer_delete(reconnect_timer_); + } + + udp_.reset(); + mqtt_.reset(); + + if (event_group_handle_ != nullptr) { + vEventGroupDelete(event_group_handle_); + } +} + +bool MqttProtocol::Start() { + return StartMqttClient(false); +} + +bool MqttProtocol::StartMqttClient(bool report_error) { + if (mqtt_ != nullptr) { + ESP_LOGW(TAG, "Mqtt client already started"); + mqtt_.reset(); + } + + Settings settings("mqtt", false); + auto endpoint = settings.GetString("endpoint"); + auto client_id = settings.GetString("client_id"); + auto username = settings.GetString("username"); + auto password = settings.GetString("password"); + int keepalive_interval = settings.GetInt("keepalive", 240); + publish_topic_ = settings.GetString("publish_topic"); + + if (endpoint.empty()) { + ESP_LOGW(TAG, "MQTT endpoint is not specified"); + if (report_error) { + SetError(Lang::Strings::SERVER_NOT_FOUND); + } + return false; + } + + auto network = Board::GetInstance().GetNetwork(); + mqtt_ = network->CreateMqtt(0); + mqtt_->SetKeepAlive(keepalive_interval); + + mqtt_->OnDisconnected([this]() { + if (on_disconnected_ != nullptr) { + on_disconnected_(); + } + ESP_LOGI(TAG, "MQTT disconnected, schedule reconnect in %d seconds", MQTT_RECONNECT_INTERVAL_MS / 1000); + esp_timer_start_once(reconnect_timer_, MQTT_RECONNECT_INTERVAL_MS * 1000); + }); + + mqtt_->OnConnected([this]() { + if (on_connected_ != nullptr) { + on_connected_(); + } + esp_timer_stop(reconnect_timer_); + }); + + mqtt_->OnMessage([this](const std::string& topic, const std::string& payload) { + cJSON* root = cJSON_Parse(payload.c_str()); + if (root == nullptr) { + ESP_LOGE(TAG, "Failed to parse json message %s", payload.c_str()); + return; + } + cJSON* type = cJSON_GetObjectItem(root, "type"); + if (!cJSON_IsString(type)) { + ESP_LOGE(TAG, "Message type is invalid"); + cJSON_Delete(root); + return; + } + + if (strcmp(type->valuestring, "hello") == 0) { + ParseServerHello(root); + } else if (strcmp(type->valuestring, "goodbye") == 0) { + auto session_id = cJSON_GetObjectItem(root, "session_id"); + ESP_LOGI(TAG, "Received goodbye message, session_id: %s", session_id ? session_id->valuestring : "null"); + if (session_id == nullptr || session_id_ == session_id->valuestring) { + Application::GetInstance().Schedule([this]() { + CloseAudioChannel(); + }); + } + } else if (on_incoming_json_ != nullptr) { + on_incoming_json_(root); + } + cJSON_Delete(root); + last_incoming_time_ = std::chrono::steady_clock::now(); + }); + + ESP_LOGI(TAG, "Connecting to endpoint %s", endpoint.c_str()); + std::string broker_address; + int broker_port = 8883; + size_t pos = endpoint.find(':'); + if (pos != std::string::npos) { + broker_address = endpoint.substr(0, pos); + broker_port = std::stoi(endpoint.substr(pos + 1)); + } else { + broker_address = endpoint; + } + if (!mqtt_->Connect(broker_address, broker_port, client_id, username, password)) { + ESP_LOGE(TAG, "Failed to connect to endpoint, code=%d", mqtt_->GetLastError()); + SetError(Lang::Strings::SERVER_NOT_CONNECTED); + return false; + } + + ESP_LOGI(TAG, "Connected to endpoint"); + return true; +} + +bool MqttProtocol::SendText(const std::string& text) { + if (publish_topic_.empty()) { + return false; + } + if (!mqtt_->Publish(publish_topic_, text)) { + ESP_LOGE(TAG, "Failed to publish message: %s", text.c_str()); + SetError(Lang::Strings::SERVER_ERROR); + return false; + } + return true; +} + +bool MqttProtocol::SendAudio(std::unique_ptr packet) { + std::lock_guard lock(channel_mutex_); + if (udp_ == nullptr) { + return false; + } + + std::string nonce(aes_nonce_); + *(uint16_t*)&nonce[2] = htons(packet->payload.size()); + *(uint32_t*)&nonce[8] = htonl(packet->timestamp); + *(uint32_t*)&nonce[12] = htonl(++local_sequence_); + + std::string encrypted; + encrypted.resize(aes_nonce_.size() + packet->payload.size()); + memcpy(encrypted.data(), nonce.data(), nonce.size()); + + size_t nc_off = 0; + uint8_t stream_block[16] = {0}; + if (mbedtls_aes_crypt_ctr(&aes_ctx_, packet->payload.size(), &nc_off, (uint8_t*)nonce.c_str(), stream_block, + (uint8_t*)packet->payload.data(), (uint8_t*)&encrypted[nonce.size()]) != 0) { + ESP_LOGE(TAG, "Failed to encrypt audio data"); + return false; + } + + return udp_->Send(encrypted) > 0; +} + +void MqttProtocol::CloseAudioChannel() { + { + std::lock_guard lock(channel_mutex_); + udp_.reset(); + } + + std::string message = "{"; + message += "\"session_id\":\"" + session_id_ + "\","; + message += "\"type\":\"goodbye\""; + message += "}"; + SendText(message); + + if (on_audio_channel_closed_ != nullptr) { + on_audio_channel_closed_(); + } +} + +bool MqttProtocol::OpenAudioChannel() { + if (mqtt_ == nullptr || !mqtt_->IsConnected()) { + ESP_LOGI(TAG, "MQTT is not connected, try to connect now"); + if (!StartMqttClient(true)) { + return false; + } + } + + error_occurred_ = false; + session_id_ = ""; + xEventGroupClearBits(event_group_handle_, MQTT_PROTOCOL_SERVER_HELLO_EVENT); + + auto message = GetHelloMessage(); + if (!SendText(message)) { + return false; + } + + // 等待服务器响应 + EventBits_t bits = xEventGroupWaitBits(event_group_handle_, MQTT_PROTOCOL_SERVER_HELLO_EVENT, pdTRUE, pdFALSE, pdMS_TO_TICKS(10000)); + if (!(bits & MQTT_PROTOCOL_SERVER_HELLO_EVENT)) { + ESP_LOGE(TAG, "Failed to receive server hello"); + SetError(Lang::Strings::SERVER_TIMEOUT); + return false; + } + + std::lock_guard lock(channel_mutex_); + auto network = Board::GetInstance().GetNetwork(); + udp_ = network->CreateUdp(2); + udp_->OnMessage([this](const std::string& data) { + /* + * UDP Encrypted OPUS Packet Format: + * |type 1u|flags 1u|payload_len 2u|ssrc 4u|timestamp 4u|sequence 4u| + * |payload payload_len| + */ + if (data.size() < sizeof(aes_nonce_)) { + ESP_LOGE(TAG, "Invalid audio packet size: %u", data.size()); + return; + } + if (data[0] != 0x01) { + ESP_LOGE(TAG, "Invalid audio packet type: %x", data[0]); + return; + } + uint32_t timestamp = ntohl(*(uint32_t*)&data[8]); + uint32_t sequence = ntohl(*(uint32_t*)&data[12]); + if (sequence < remote_sequence_) { + ESP_LOGW(TAG, "Received audio packet with old sequence: %lu, expected: %lu", sequence, remote_sequence_); + return; + } + if (sequence != remote_sequence_ + 1) { + ESP_LOGW(TAG, "Received audio packet with wrong sequence: %lu, expected: %lu", sequence, remote_sequence_ + 1); + } + + size_t decrypted_size = data.size() - aes_nonce_.size(); + size_t nc_off = 0; + uint8_t stream_block[16] = {0}; + auto nonce = (uint8_t*)data.data(); + auto encrypted = (uint8_t*)data.data() + aes_nonce_.size(); + auto packet = std::make_unique(); + packet->sample_rate = server_sample_rate_; + packet->frame_duration = server_frame_duration_; + packet->timestamp = timestamp; + packet->payload.resize(decrypted_size); + int ret = mbedtls_aes_crypt_ctr(&aes_ctx_, decrypted_size, &nc_off, nonce, stream_block, encrypted, (uint8_t*)packet->payload.data()); + if (ret != 0) { + ESP_LOGE(TAG, "Failed to decrypt audio data, ret: %d", ret); + return; + } + if (on_incoming_audio_ != nullptr) { + on_incoming_audio_(std::move(packet)); + } + remote_sequence_ = sequence; + last_incoming_time_ = std::chrono::steady_clock::now(); + }); + + udp_->Connect(udp_server_, udp_port_); + + if (on_audio_channel_opened_ != nullptr) { + on_audio_channel_opened_(); + } + return true; +} + +std::string MqttProtocol::GetHelloMessage() { + // 发送 hello 消息申请 UDP 通道 + cJSON* root = cJSON_CreateObject(); + cJSON_AddStringToObject(root, "type", "hello"); + cJSON_AddNumberToObject(root, "version", 3); + cJSON_AddStringToObject(root, "transport", "udp"); + cJSON* features = cJSON_CreateObject(); +#if CONFIG_USE_SERVER_AEC + cJSON_AddBoolToObject(features, "aec", true); +#endif + cJSON_AddBoolToObject(features, "mcp", true); + cJSON_AddItemToObject(root, "features", features); + cJSON* audio_params = cJSON_CreateObject(); + cJSON_AddStringToObject(audio_params, "format", "opus"); + cJSON_AddNumberToObject(audio_params, "sample_rate", 16000); + cJSON_AddNumberToObject(audio_params, "channels", 1); + cJSON_AddNumberToObject(audio_params, "frame_duration", OPUS_FRAME_DURATION_MS); + cJSON_AddItemToObject(root, "audio_params", audio_params); + auto json_str = cJSON_PrintUnformatted(root); + std::string message(json_str); + cJSON_free(json_str); + cJSON_Delete(root); + return message; +} + +void MqttProtocol::ParseServerHello(const cJSON* root) { + auto transport = cJSON_GetObjectItem(root, "transport"); + if (transport == nullptr || strcmp(transport->valuestring, "udp") != 0) { + ESP_LOGE(TAG, "Unsupported transport: %s", transport->valuestring); + return; + } + + auto session_id = cJSON_GetObjectItem(root, "session_id"); + if (cJSON_IsString(session_id)) { + session_id_ = session_id->valuestring; + ESP_LOGI(TAG, "Session ID: %s", session_id_.c_str()); + } + + // Get sample rate from hello message + auto audio_params = cJSON_GetObjectItem(root, "audio_params"); + if (cJSON_IsObject(audio_params)) { + auto sample_rate = cJSON_GetObjectItem(audio_params, "sample_rate"); + if (cJSON_IsNumber(sample_rate)) { + server_sample_rate_ = sample_rate->valueint; + } + auto frame_duration = cJSON_GetObjectItem(audio_params, "frame_duration"); + if (cJSON_IsNumber(frame_duration)) { + server_frame_duration_ = frame_duration->valueint; + } + } + + auto udp = cJSON_GetObjectItem(root, "udp"); + if (!cJSON_IsObject(udp)) { + ESP_LOGE(TAG, "UDP is not specified"); + return; + } + udp_server_ = cJSON_GetObjectItem(udp, "server")->valuestring; + udp_port_ = cJSON_GetObjectItem(udp, "port")->valueint; + auto key = cJSON_GetObjectItem(udp, "key")->valuestring; + auto nonce = cJSON_GetObjectItem(udp, "nonce")->valuestring; + + // auto encryption = cJSON_GetObjectItem(udp, "encryption")->valuestring; + // ESP_LOGI(TAG, "UDP server: %s, port: %d, encryption: %s", udp_server_.c_str(), udp_port_, encryption); + aes_nonce_ = DecodeHexString(nonce); + mbedtls_aes_init(&aes_ctx_); + mbedtls_aes_setkey_enc(&aes_ctx_, (const unsigned char*)DecodeHexString(key).c_str(), 128); + local_sequence_ = 0; + remote_sequence_ = 0; + xEventGroupSetBits(event_group_handle_, MQTT_PROTOCOL_SERVER_HELLO_EVENT); +} + +static const char hex_chars[] = "0123456789ABCDEF"; +// 辅助函数,将单个十六进制字符转换为对应的数值 +static inline uint8_t CharToHex(char c) { + if (c >= '0' && c <= '9') return c - '0'; + if (c >= 'A' && c <= 'F') return c - 'A' + 10; + if (c >= 'a' && c <= 'f') return c - 'a' + 10; + return 0; // 对于无效输入,返回0 +} + +std::string MqttProtocol::DecodeHexString(const std::string& hex_string) { + std::string decoded; + decoded.reserve(hex_string.size() / 2); + for (size_t i = 0; i < hex_string.size(); i += 2) { + char byte = (CharToHex(hex_string[i]) << 4) | CharToHex(hex_string[i + 1]); + decoded.push_back(byte); + } + return decoded; +} + +bool MqttProtocol::IsAudioChannelOpened() const { + return udp_ != nullptr && !error_occurred_ && !IsTimeout(); +} diff --git a/main/protocols/mqtt_protocol.h b/main/protocols/mqtt_protocol.h new file mode 100644 index 0000000..0b7b20a --- /dev/null +++ b/main/protocols/mqtt_protocol.h @@ -0,0 +1,60 @@ +#ifndef MQTT_PROTOCOL_H +#define MQTT_PROTOCOL_H + + +#include "protocol.h" +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#define MQTT_PING_INTERVAL_SECONDS 90 +#define MQTT_RECONNECT_INTERVAL_MS 60000 + +#define MQTT_PROTOCOL_SERVER_HELLO_EVENT (1 << 0) + +class MqttProtocol : public Protocol { +public: + MqttProtocol(); + ~MqttProtocol(); + + bool Start() override; + bool SendAudio(std::unique_ptr packet) override; + bool OpenAudioChannel() override; + void CloseAudioChannel() override; + bool IsAudioChannelOpened() const override; + +private: + EventGroupHandle_t event_group_handle_; + + std::string publish_topic_; + + std::mutex channel_mutex_; + std::unique_ptr mqtt_; + std::unique_ptr udp_; + mbedtls_aes_context aes_ctx_; + std::string aes_nonce_; + std::string udp_server_; + int udp_port_; + uint32_t local_sequence_; + uint32_t remote_sequence_; + esp_timer_handle_t reconnect_timer_; + + bool StartMqttClient(bool report_error=false); + void ParseServerHello(const cJSON* root); + std::string DecodeHexString(const std::string& hex_string); + + bool SendText(const std::string& text) override; + std::string GetHelloMessage(); +}; + + +#endif // MQTT_PROTOCOL_H diff --git a/main/protocols/protocol.cc b/main/protocols/protocol.cc new file mode 100644 index 0000000..470cc91 --- /dev/null +++ b/main/protocols/protocol.cc @@ -0,0 +1,90 @@ +#include "protocol.h" + +#include + +#define TAG "Protocol" + +void Protocol::OnIncomingJson(std::function callback) { + on_incoming_json_ = callback; +} + +void Protocol::OnIncomingAudio(std::function packet)> callback) { + on_incoming_audio_ = callback; +} + +void Protocol::OnAudioChannelOpened(std::function callback) { + on_audio_channel_opened_ = callback; +} + +void Protocol::OnAudioChannelClosed(std::function callback) { + on_audio_channel_closed_ = callback; +} + +void Protocol::OnNetworkError(std::function callback) { + on_network_error_ = callback; +} + +void Protocol::OnConnected(std::function callback) { + on_connected_ = callback; +} + +void Protocol::OnDisconnected(std::function callback) { + on_disconnected_ = callback; +} + +void Protocol::SetError(const std::string& message) { + error_occurred_ = true; + if (on_network_error_ != nullptr) { + on_network_error_(message); + } +} + +void Protocol::SendAbortSpeaking(AbortReason reason) { + std::string message = "{\"session_id\":\"" + session_id_ + "\",\"type\":\"abort\""; + if (reason == kAbortReasonWakeWordDetected) { + message += ",\"reason\":\"wake_word_detected\""; + } + message += "}"; + SendText(message); +} + +void Protocol::SendWakeWordDetected(const std::string& wake_word) { + std::string json = "{\"session_id\":\"" + session_id_ + + "\",\"type\":\"listen\",\"state\":\"detect\",\"text\":\"" + wake_word + "\"}"; + SendText(json); +} + +void Protocol::SendStartListening(ListeningMode mode) { + std::string message = "{\"session_id\":\"" + session_id_ + "\""; + message += ",\"type\":\"listen\",\"state\":\"start\""; + if (mode == kListeningModeRealtime) { + message += ",\"mode\":\"realtime\""; + } else if (mode == kListeningModeAutoStop) { + message += ",\"mode\":\"auto\""; + } else { + message += ",\"mode\":\"manual\""; + } + message += "}"; + SendText(message); +} + +void Protocol::SendStopListening() { + std::string message = "{\"session_id\":\"" + session_id_ + "\",\"type\":\"listen\",\"state\":\"stop\"}"; + SendText(message); +} + +void Protocol::SendMcpMessage(const std::string& payload) { + std::string message = "{\"session_id\":\"" + session_id_ + "\",\"type\":\"mcp\",\"payload\":" + payload + "}"; + SendText(message); +} + +bool Protocol::IsTimeout() const { + const int kTimeoutSeconds = 120; + auto now = std::chrono::steady_clock::now(); + auto duration = std::chrono::duration_cast(now - last_incoming_time_); + bool timeout = duration.count() > kTimeoutSeconds; + if (timeout) { + ESP_LOGE(TAG, "Channel timeout %ld seconds", (long)duration.count()); + } + return timeout; +} diff --git a/main/protocols/protocol.h b/main/protocols/protocol.h new file mode 100644 index 0000000..17ab315 --- /dev/null +++ b/main/protocols/protocol.h @@ -0,0 +1,98 @@ +#ifndef PROTOCOL_H +#define PROTOCOL_H + +#include +#include +#include +#include +#include + +struct AudioStreamPacket { + int sample_rate = 0; + int frame_duration = 0; + uint32_t timestamp = 0; + std::vector payload; +}; + +struct BinaryProtocol2 { + uint16_t version; + uint16_t type; // Message type (0: OPUS, 1: JSON) + uint32_t reserved; // Reserved for future use + uint32_t timestamp; // Timestamp in milliseconds (used for server-side AEC) + uint32_t payload_size; // Payload size in bytes + uint8_t payload[]; // Payload data +} __attribute__((packed)); + +struct BinaryProtocol3 { + uint8_t type; + uint8_t reserved; + uint16_t payload_size; + uint8_t payload[]; +} __attribute__((packed)); + +enum AbortReason { + kAbortReasonNone, + kAbortReasonWakeWordDetected +}; + +enum ListeningMode { + kListeningModeAutoStop, + kListeningModeManualStop, + kListeningModeRealtime // 需要 AEC 支持 +}; + +class Protocol { +public: + virtual ~Protocol() = default; + + inline int server_sample_rate() const { + return server_sample_rate_; + } + inline int server_frame_duration() const { + return server_frame_duration_; + } + inline const std::string& session_id() const { + return session_id_; + } + + void OnIncomingAudio(std::function packet)> callback); + void OnIncomingJson(std::function callback); + void OnAudioChannelOpened(std::function callback); + void OnAudioChannelClosed(std::function callback); + void OnNetworkError(std::function callback); + void OnConnected(std::function callback); + void OnDisconnected(std::function callback); + + virtual bool Start() = 0; + virtual bool OpenAudioChannel() = 0; + virtual void CloseAudioChannel() = 0; + virtual bool IsAudioChannelOpened() const = 0; + virtual bool SendAudio(std::unique_ptr packet) = 0; + virtual void SendWakeWordDetected(const std::string& wake_word); + virtual void SendStartListening(ListeningMode mode); + virtual void SendStopListening(); + virtual void SendAbortSpeaking(AbortReason reason); + virtual void SendMcpMessage(const std::string& message); + +protected: + std::function on_incoming_json_; + std::function packet)> on_incoming_audio_; + std::function on_audio_channel_opened_; + std::function on_audio_channel_closed_; + std::function on_network_error_; + std::function on_connected_; + std::function on_disconnected_; + + int server_sample_rate_ = 24000; + int server_frame_duration_ = 60; + bool error_occurred_ = false; + std::string session_id_; + std::chrono::time_point last_incoming_time_; + + virtual bool SendText(const std::string& text) = 0; + virtual void SetError(const std::string& message); + virtual bool IsTimeout() const; +}; + +#endif // PROTOCOL_H + diff --git a/main/protocols/websocket_protocol.cc b/main/protocols/websocket_protocol.cc new file mode 100644 index 0000000..a8f8cf3 --- /dev/null +++ b/main/protocols/websocket_protocol.cc @@ -0,0 +1,253 @@ +#include "websocket_protocol.h" +#include "board.h" +#include "system_info.h" +#include "application.h" +#include "settings.h" + +#include +#include +#include +#include +#include "assets/lang_config.h" + +#define TAG "WS" + +WebsocketProtocol::WebsocketProtocol() { + event_group_handle_ = xEventGroupCreate(); +} + +WebsocketProtocol::~WebsocketProtocol() { + vEventGroupDelete(event_group_handle_); +} + +bool WebsocketProtocol::Start() { + // Only connect to server when audio channel is needed + return true; +} + +bool WebsocketProtocol::SendAudio(std::unique_ptr packet) { + if (websocket_ == nullptr || !websocket_->IsConnected()) { + return false; + } + + if (version_ == 2) { + std::string serialized; + serialized.resize(sizeof(BinaryProtocol2) + packet->payload.size()); + auto bp2 = (BinaryProtocol2*)serialized.data(); + bp2->version = htons(version_); + bp2->type = 0; + bp2->reserved = 0; + bp2->timestamp = htonl(packet->timestamp); + bp2->payload_size = htonl(packet->payload.size()); + memcpy(bp2->payload, packet->payload.data(), packet->payload.size()); + + return websocket_->Send(serialized.data(), serialized.size(), true); + } else if (version_ == 3) { + std::string serialized; + serialized.resize(sizeof(BinaryProtocol3) + packet->payload.size()); + auto bp3 = (BinaryProtocol3*)serialized.data(); + bp3->type = 0; + bp3->reserved = 0; + bp3->payload_size = htons(packet->payload.size()); + memcpy(bp3->payload, packet->payload.data(), packet->payload.size()); + + return websocket_->Send(serialized.data(), serialized.size(), true); + } else { + return websocket_->Send(packet->payload.data(), packet->payload.size(), true); + } +} + +bool WebsocketProtocol::SendText(const std::string& text) { + if (websocket_ == nullptr || !websocket_->IsConnected()) { + return false; + } + + if (!websocket_->Send(text)) { + ESP_LOGE(TAG, "Failed to send text: %s", text.c_str()); + SetError(Lang::Strings::SERVER_ERROR); + return false; + } + + return true; +} + +bool WebsocketProtocol::IsAudioChannelOpened() const { + return websocket_ != nullptr && websocket_->IsConnected() && !error_occurred_ && !IsTimeout(); +} + +void WebsocketProtocol::CloseAudioChannel() { + websocket_.reset(); +} + +bool WebsocketProtocol::OpenAudioChannel() { + Settings settings("websocket", false); + std::string url = settings.GetString("url"); + std::string token = settings.GetString("token"); + int version = settings.GetInt("version"); + if (version != 0) { + version_ = version; + } + + error_occurred_ = false; + + auto network = Board::GetInstance().GetNetwork(); + websocket_ = network->CreateWebSocket(1); + if (websocket_ == nullptr) { + ESP_LOGE(TAG, "Failed to create websocket"); + return false; + } + + if (!token.empty()) { + // If token not has a space, add "Bearer " prefix + if (token.find(" ") == std::string::npos) { + token = "Bearer " + token; + } + websocket_->SetHeader("Authorization", token.c_str()); + } + websocket_->SetHeader("Protocol-Version", std::to_string(version_).c_str()); + websocket_->SetHeader("Device-Id", SystemInfo::GetMacAddress().c_str()); + websocket_->SetHeader("Client-Id", Board::GetInstance().GetUuid().c_str()); + + websocket_->OnData([this](const char* data, size_t len, bool binary) { + if (binary) { + if (on_incoming_audio_ != nullptr) { + if (version_ == 2) { + BinaryProtocol2* bp2 = (BinaryProtocol2*)data; + bp2->version = ntohs(bp2->version); + bp2->type = ntohs(bp2->type); + bp2->timestamp = ntohl(bp2->timestamp); + bp2->payload_size = ntohl(bp2->payload_size); + auto payload = (uint8_t*)bp2->payload; + on_incoming_audio_(std::make_unique(AudioStreamPacket{ + .sample_rate = server_sample_rate_, + .frame_duration = server_frame_duration_, + .timestamp = bp2->timestamp, + .payload = std::vector(payload, payload + bp2->payload_size) + })); + } else if (version_ == 3) { + BinaryProtocol3* bp3 = (BinaryProtocol3*)data; + bp3->type = bp3->type; + bp3->payload_size = ntohs(bp3->payload_size); + auto payload = (uint8_t*)bp3->payload; + on_incoming_audio_(std::make_unique(AudioStreamPacket{ + .sample_rate = server_sample_rate_, + .frame_duration = server_frame_duration_, + .timestamp = 0, + .payload = std::vector(payload, payload + bp3->payload_size) + })); + } else { + on_incoming_audio_(std::make_unique(AudioStreamPacket{ + .sample_rate = server_sample_rate_, + .frame_duration = server_frame_duration_, + .timestamp = 0, + .payload = std::vector((uint8_t*)data, (uint8_t*)data + len) + })); + } + } + } else { + // Parse JSON data + auto root = cJSON_Parse(data); + auto type = cJSON_GetObjectItem(root, "type"); + if (cJSON_IsString(type)) { + if (strcmp(type->valuestring, "hello") == 0) { + ParseServerHello(root); + } else { + if (on_incoming_json_ != nullptr) { + on_incoming_json_(root); + } + } + } else { + ESP_LOGE(TAG, "Missing message type, data: %s", data); + } + cJSON_Delete(root); + } + last_incoming_time_ = std::chrono::steady_clock::now(); + }); + + websocket_->OnDisconnected([this]() { + ESP_LOGI(TAG, "Websocket disconnected"); + if (on_audio_channel_closed_ != nullptr) { + on_audio_channel_closed_(); + } + }); + + ESP_LOGI(TAG, "Connecting to websocket server: %s with version: %d", url.c_str(), version_); + if (!websocket_->Connect(url.c_str())) { + ESP_LOGE(TAG, "Failed to connect to websocket server, code=%d", websocket_->GetLastError()); + SetError(Lang::Strings::SERVER_NOT_CONNECTED); + return false; + } + + // Send hello message to describe the client + auto message = GetHelloMessage(); + if (!SendText(message)) { + return false; + } + + // Wait for server hello + EventBits_t bits = xEventGroupWaitBits(event_group_handle_, WEBSOCKET_PROTOCOL_SERVER_HELLO_EVENT, pdTRUE, pdFALSE, pdMS_TO_TICKS(10000)); + if (!(bits & WEBSOCKET_PROTOCOL_SERVER_HELLO_EVENT)) { + ESP_LOGE(TAG, "Failed to receive server hello"); + SetError(Lang::Strings::SERVER_TIMEOUT); + return false; + } + + if (on_audio_channel_opened_ != nullptr) { + on_audio_channel_opened_(); + } + + return true; +} + +std::string WebsocketProtocol::GetHelloMessage() { + // keys: message type, version, audio_params (format, sample_rate, channels) + cJSON* root = cJSON_CreateObject(); + cJSON_AddStringToObject(root, "type", "hello"); + cJSON_AddNumberToObject(root, "version", version_); + cJSON* features = cJSON_CreateObject(); +#if CONFIG_USE_SERVER_AEC + cJSON_AddBoolToObject(features, "aec", true); +#endif + cJSON_AddBoolToObject(features, "mcp", true); + cJSON_AddItemToObject(root, "features", features); + cJSON_AddStringToObject(root, "transport", "websocket"); + cJSON* audio_params = cJSON_CreateObject(); + cJSON_AddStringToObject(audio_params, "format", "opus"); + cJSON_AddNumberToObject(audio_params, "sample_rate", 16000); + cJSON_AddNumberToObject(audio_params, "channels", 1); + cJSON_AddNumberToObject(audio_params, "frame_duration", OPUS_FRAME_DURATION_MS); + cJSON_AddItemToObject(root, "audio_params", audio_params); + auto json_str = cJSON_PrintUnformatted(root); + std::string message(json_str); + cJSON_free(json_str); + cJSON_Delete(root); + return message; +} + +void WebsocketProtocol::ParseServerHello(const cJSON* root) { + auto transport = cJSON_GetObjectItem(root, "transport"); + if (transport == nullptr || strcmp(transport->valuestring, "websocket") != 0) { + ESP_LOGE(TAG, "Unsupported transport: %s", transport->valuestring); + return; + } + + auto session_id = cJSON_GetObjectItem(root, "session_id"); + if (cJSON_IsString(session_id)) { + session_id_ = session_id->valuestring; + ESP_LOGI(TAG, "Session ID: %s", session_id_.c_str()); + } + + auto audio_params = cJSON_GetObjectItem(root, "audio_params"); + if (cJSON_IsObject(audio_params)) { + auto sample_rate = cJSON_GetObjectItem(audio_params, "sample_rate"); + if (cJSON_IsNumber(sample_rate)) { + server_sample_rate_ = sample_rate->valueint; + } + auto frame_duration = cJSON_GetObjectItem(audio_params, "frame_duration"); + if (cJSON_IsNumber(frame_duration)) { + server_frame_duration_ = frame_duration->valueint; + } + } + + xEventGroupSetBits(event_group_handle_, WEBSOCKET_PROTOCOL_SERVER_HELLO_EVENT); +} diff --git a/main/protocols/websocket_protocol.h b/main/protocols/websocket_protocol.h new file mode 100644 index 0000000..8c7dd65 --- /dev/null +++ b/main/protocols/websocket_protocol.h @@ -0,0 +1,34 @@ +#ifndef _WEBSOCKET_PROTOCOL_H_ +#define _WEBSOCKET_PROTOCOL_H_ + + +#include "protocol.h" + +#include +#include +#include + +#define WEBSOCKET_PROTOCOL_SERVER_HELLO_EVENT (1 << 0) + +class WebsocketProtocol : public Protocol { +public: + WebsocketProtocol(); + ~WebsocketProtocol(); + + bool Start() override; + bool SendAudio(std::unique_ptr packet) override; + bool OpenAudioChannel() override; + void CloseAudioChannel() override; + bool IsAudioChannelOpened() const override; + +private: + EventGroupHandle_t event_group_handle_; + std::unique_ptr websocket_; + int version_ = 1; + + void ParseServerHello(const cJSON* root); + bool SendText(const std::string& text) override; + std::string GetHelloMessage(); +}; + +#endif diff --git a/main/settings.cc b/main/settings.cc new file mode 100644 index 0000000..3b40622 --- /dev/null +++ b/main/settings.cc @@ -0,0 +1,108 @@ +#include "settings.h" + +#include +#include + +#define TAG "Settings" + +Settings::Settings(const std::string& ns, bool read_write) : ns_(ns), read_write_(read_write) { + nvs_open(ns.c_str(), read_write_ ? NVS_READWRITE : NVS_READONLY, &nvs_handle_); +} + +Settings::~Settings() { + if (nvs_handle_ != 0) { + if (read_write_ && dirty_) { + ESP_ERROR_CHECK(nvs_commit(nvs_handle_)); + } + nvs_close(nvs_handle_); + } +} + +std::string Settings::GetString(const std::string& key, const std::string& default_value) { + if (nvs_handle_ == 0) { + return default_value; + } + + size_t length = 0; + if (nvs_get_str(nvs_handle_, key.c_str(), nullptr, &length) != ESP_OK) { + return default_value; + } + + std::string value; + value.resize(length); + ESP_ERROR_CHECK(nvs_get_str(nvs_handle_, key.c_str(), value.data(), &length)); + while (!value.empty() && value.back() == '\0') { + value.pop_back(); + } + return value; +} + +void Settings::SetString(const std::string& key, const std::string& value) { + if (read_write_) { + ESP_ERROR_CHECK(nvs_set_str(nvs_handle_, key.c_str(), value.c_str())); + dirty_ = true; + } else { + ESP_LOGW(TAG, "Namespace %s is not open for writing", ns_.c_str()); + } +} + +int32_t Settings::GetInt(const std::string& key, int32_t default_value) { + if (nvs_handle_ == 0) { + return default_value; + } + + int32_t value; + if (nvs_get_i32(nvs_handle_, key.c_str(), &value) != ESP_OK) { + return default_value; + } + return value; +} + +void Settings::SetInt(const std::string& key, int32_t value) { + if (read_write_) { + ESP_ERROR_CHECK(nvs_set_i32(nvs_handle_, key.c_str(), value)); + dirty_ = true; + } else { + ESP_LOGW(TAG, "Namespace %s is not open for writing", ns_.c_str()); + } +} + +bool Settings::GetBool(const std::string& key, bool default_value) { + if (nvs_handle_ == 0) { + return default_value; + } + + uint8_t value; + if (nvs_get_u8(nvs_handle_, key.c_str(), &value) != ESP_OK) { + return default_value; + } + return value != 0; +} + +void Settings::SetBool(const std::string& key, bool value) { + if (read_write_) { + ESP_ERROR_CHECK(nvs_set_u8(nvs_handle_, key.c_str(), value ? 1 : 0)); + dirty_ = true; + } else { + ESP_LOGW(TAG, "Namespace %s is not open for writing", ns_.c_str()); + } +} + +void Settings::EraseKey(const std::string& key) { + if (read_write_) { + auto ret = nvs_erase_key(nvs_handle_, key.c_str()); + if (ret != ESP_ERR_NVS_NOT_FOUND) { + ESP_ERROR_CHECK(ret); + } + } else { + ESP_LOGW(TAG, "Namespace %s is not open for writing", ns_.c_str()); + } +} + +void Settings::EraseAll() { + if (read_write_) { + ESP_ERROR_CHECK(nvs_erase_all(nvs_handle_)); + } else { + ESP_LOGW(TAG, "Namespace %s is not open for writing", ns_.c_str()); + } +} diff --git a/main/settings.h b/main/settings.h new file mode 100644 index 0000000..7eb596e --- /dev/null +++ b/main/settings.h @@ -0,0 +1,28 @@ +#ifndef SETTINGS_H +#define SETTINGS_H + +#include +#include + +class Settings { +public: + Settings(const std::string& ns, bool read_write = false); + ~Settings(); + + std::string GetString(const std::string& key, const std::string& default_value = ""); + void SetString(const std::string& key, const std::string& value); + int32_t GetInt(const std::string& key, int32_t default_value = 0); + void SetInt(const std::string& key, int32_t value); + bool GetBool(const std::string& key, bool default_value = false); + void SetBool(const std::string& key, bool value); + void EraseKey(const std::string& key); + void EraseAll(); + +private: + std::string ns_; + nvs_handle_t nvs_handle_ = 0; + bool read_write_ = false; + bool dirty_ = false; +}; + +#endif diff --git a/main/system_info.cc b/main/system_info.cc new file mode 100644 index 0000000..51b0072 --- /dev/null +++ b/main/system_info.cc @@ -0,0 +1,151 @@ +#include "system_info.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#if CONFIG_IDF_TARGET_ESP32P4 +#include "esp_wifi_remote.h" +#endif + +#define TAG "SystemInfo" + +size_t SystemInfo::GetFlashSize() { + uint32_t flash_size; + if (esp_flash_get_size(NULL, &flash_size) != ESP_OK) { + ESP_LOGE(TAG, "Failed to get flash size"); + return 0; + } + return (size_t)flash_size; +} + +size_t SystemInfo::GetMinimumFreeHeapSize() { + return esp_get_minimum_free_heap_size(); +} + +size_t SystemInfo::GetFreeHeapSize() { + return esp_get_free_heap_size(); +} + +std::string SystemInfo::GetMacAddress() { + uint8_t mac[6]; +#if CONFIG_IDF_TARGET_ESP32P4 + esp_wifi_get_mac(WIFI_IF_STA, mac); +#else + esp_read_mac(mac, ESP_MAC_WIFI_STA); +#endif + char mac_str[18]; + snprintf(mac_str, sizeof(mac_str), "%02x:%02x:%02x:%02x:%02x:%02x", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); + return std::string(mac_str); +} + +std::string SystemInfo::GetChipModelName() { + return std::string(CONFIG_IDF_TARGET); +} + +std::string SystemInfo::GetUserAgent() { + auto app_desc = esp_app_get_description(); + auto user_agent = std::string(BOARD_NAME "/") + app_desc->version; + return user_agent; +} + +esp_err_t SystemInfo::PrintTaskCpuUsage(TickType_t xTicksToWait) { + #define ARRAY_SIZE_OFFSET 5 + TaskStatus_t *start_array = NULL, *end_array = NULL; + UBaseType_t start_array_size, end_array_size; + configRUN_TIME_COUNTER_TYPE start_run_time, end_run_time; + esp_err_t ret; + uint32_t total_elapsed_time; + + //Allocate array to store current task states + start_array_size = uxTaskGetNumberOfTasks() + ARRAY_SIZE_OFFSET; + start_array = (TaskStatus_t*)malloc(sizeof(TaskStatus_t) * start_array_size); + if (start_array == NULL) { + ret = ESP_ERR_NO_MEM; + goto exit; + } + //Get current task states + start_array_size = uxTaskGetSystemState(start_array, start_array_size, &start_run_time); + if (start_array_size == 0) { + ret = ESP_ERR_INVALID_SIZE; + goto exit; + } + + vTaskDelay(xTicksToWait); + + //Allocate array to store tasks states post delay + end_array_size = uxTaskGetNumberOfTasks() + ARRAY_SIZE_OFFSET; + end_array = (TaskStatus_t*)malloc(sizeof(TaskStatus_t) * end_array_size); + if (end_array == NULL) { + ret = ESP_ERR_NO_MEM; + goto exit; + } + //Get post delay task states + end_array_size = uxTaskGetSystemState(end_array, end_array_size, &end_run_time); + if (end_array_size == 0) { + ret = ESP_ERR_INVALID_SIZE; + goto exit; + } + + //Calculate total_elapsed_time in units of run time stats clock period. + total_elapsed_time = (end_run_time - start_run_time); + if (total_elapsed_time == 0) { + ret = ESP_ERR_INVALID_STATE; + goto exit; + } + + printf("| Task | Run Time | Percentage\n"); + //Match each task in start_array to those in the end_array + for (int i = 0; i < start_array_size; i++) { + int k = -1; + for (int j = 0; j < end_array_size; j++) { + if (start_array[i].xHandle == end_array[j].xHandle) { + k = j; + //Mark that task have been matched by overwriting their handles + start_array[i].xHandle = NULL; + end_array[j].xHandle = NULL; + break; + } + } + //Check if matching task found + if (k >= 0) { + uint32_t task_elapsed_time = end_array[k].ulRunTimeCounter - start_array[i].ulRunTimeCounter; + uint32_t percentage_time = (task_elapsed_time * 100UL) / (total_elapsed_time * CONFIG_FREERTOS_NUMBER_OF_CORES); + printf("| %-16s | %8lu | %4lu%%\n", start_array[i].pcTaskName, task_elapsed_time, percentage_time); + } + } + + //Print unmatched tasks + for (int i = 0; i < start_array_size; i++) { + if (start_array[i].xHandle != NULL) { + printf("| %s | Deleted\n", start_array[i].pcTaskName); + } + } + for (int i = 0; i < end_array_size; i++) { + if (end_array[i].xHandle != NULL) { + printf("| %s | Created\n", end_array[i].pcTaskName); + } + } + ret = ESP_OK; + +exit: //Common return path + free(start_array); + free(end_array); + return ret; +} + +void SystemInfo::PrintTaskList() { + char buffer[1000]; + vTaskList(buffer); + ESP_LOGI(TAG, "Task list: \n%s", buffer); +} + +void SystemInfo::PrintHeapStats() { + int free_sram = heap_caps_get_free_size(MALLOC_CAP_INTERNAL); + int min_free_sram = heap_caps_get_minimum_free_size(MALLOC_CAP_INTERNAL); + ESP_LOGI(TAG, "free sram: %u minimal sram: %u", free_sram, min_free_sram); +} diff --git a/main/system_info.h b/main/system_info.h new file mode 100644 index 0000000..a466d71 --- /dev/null +++ b/main/system_info.h @@ -0,0 +1,22 @@ +#ifndef _SYSTEM_INFO_H_ +#define _SYSTEM_INFO_H_ + +#include + +#include +#include + +class SystemInfo { +public: + static size_t GetFlashSize(); + static size_t GetMinimumFreeHeapSize(); + static size_t GetFreeHeapSize(); + static std::string GetMacAddress(); + static std::string GetChipModelName(); + static std::string GetUserAgent(); + static esp_err_t PrintTaskCpuUsage(TickType_t xTicksToWait); + static void PrintTaskList(); + static void PrintHeapStats(); +}; + +#endif // _SYSTEM_INFO_H_ diff --git a/main/uart_component.cc b/main/uart_component.cc new file mode 100644 index 0000000..b44aa79 --- /dev/null +++ b/main/uart_component.cc @@ -0,0 +1,38 @@ +#include "uart_component.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include + +// 初始化 ESP32 → RP2040 的 UART 通信 +// 波特率 115200,8 数据位,无校验,1 停止位,无流控 +void uart_init_component() { + uart_config_t uart_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, + }; + uart_param_config(UART_PORT_NUM, &uart_config); + // GPIO17=TX(发送到 RP2040 的 GP5/RX),GPIO18=RX(接收 RP2040 的 GP4/TX) + uart_set_pin(UART_PORT_NUM, TXD_PIN, RXD_PIN, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); + uart_driver_install(UART_PORT_NUM, BUF_SIZE, 0, 0, NULL, 0); +} + +// 发送状态字符串给 RP2040,末尾自动添加 \r\n +// RP2040 的 main.py 通过 coms.esp_read() 按 \n 分割解析 +// 支持的状态字符串:idle / listening / speaking / thinking / neutral / happy 等 +void uart_send_string(const char* str) { + uart_write_bytes(UART_PORT_NUM, str, strlen(str)); + uart_write_bytes(UART_PORT_NUM, "\r\n", 2); +} + +// 发送说话开始信号(预留接口,RP2040 当前未使用) +void uart_signal_start() { + uart_send_string("[SPEAK_START]\n"); +} + +// 发送说话停止信号(预留接口,RP2040 当前未使用) +void uart_signal_stop() { + uart_send_string("[SPEAK_STOP]\n"); +} diff --git a/main/uart_component.h b/main/uart_component.h new file mode 100644 index 0000000..c713de5 --- /dev/null +++ b/main/uart_component.h @@ -0,0 +1,20 @@ +#pragma once +#include "driver/uart.h" + +// ESP32 → RP2040 的 UART 通信引脚定义 +// ESP32 的 GPIO17(TX) 连接 RP2040 的 GP5(RX) +// ESP32 的 GPIO18(RX) 连接 RP2040 的 GP4(TX) +#define TXD_PIN 17 +#define RXD_PIN 18 +#define UART_PORT_NUM UART_NUM_1 // 使用 UART1(UART0 用于调试日志) +#define BUF_SIZE 1024 + +// 初始化 UART 组件(115200 波特率,8N1) +void uart_init_component(); +// 发送状态字符串给 RP2040(如 "speaking"、"listening"、"idle" 等) +// RP2040 收到后驱动 9 个舵机执行对应动画 +void uart_send_string(const char* str); +// 发送说话开始信号 +void uart_signal_start(); +// 发送说话停止信号 +void uart_signal_stop(); diff --git a/partitions/v1/16m.csv b/partitions/v1/16m.csv new file mode 100644 index 0000000..bc3a0e8 --- /dev/null +++ b/partitions/v1/16m.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0xF0000, +ota_0, app, ota_0, 0x100000, 6M, +ota_1, app, ota_1, 0x700000, 6M, diff --git a/partitions/v1/16m_custom_wakeword.csv b/partitions/v1/16m_custom_wakeword.csv new file mode 100644 index 0000000..868294e --- /dev/null +++ b/partitions/v1/16m_custom_wakeword.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0x3f0000, +ota_0, app, ota_0, 0x400000, 6M, +ota_1, app, ota_1, 0xa00000, 6M, \ No newline at end of file diff --git a/partitions/v1/16m_echoear.csv b/partitions/v1/16m_echoear.csv new file mode 100644 index 0000000..543c92c --- /dev/null +++ b/partitions/v1/16m_echoear.csv @@ -0,0 +1,9 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0xF0000, +ota_0, app, ota_0, 0x100000, 5M, +ota_1, app, ota_1, 0x700000, 5M, +assets_A, data, spiffs, , 4000K, diff --git a/partitions/v1/32m.csv b/partitions/v1/32m.csv new file mode 100644 index 0000000..e95eb22 --- /dev/null +++ b/partitions/v1/32m.csv @@ -0,0 +1,10 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvsfactory, data, nvs, , 200K, +nvs, data, nvs, , 840K, +otadata, data, ota, , 0x2000, +phy_init, data, phy, , 0x1000, +model, data, spiffs, , 0xF0000, +# According to scripts/versions.py, app partition must be aligned to 1MB +ota_0, app, ota_0, 0x200000, 12M, +ota_1, app, ota_1, , 12M, diff --git a/partitions/v1/4m.csv b/partitions/v1/4m.csv new file mode 100644 index 0000000..101349f --- /dev/null +++ b/partitions/v1/4m.csv @@ -0,0 +1,7 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0xF0000, +factory, app, factory, 0x100000, 3M, diff --git a/partitions/v1/4m_esp-hi.csv b/partitions/v1/4m_esp-hi.csv new file mode 100644 index 0000000..90c9c43 --- /dev/null +++ b/partitions/v1/4m_esp-hi.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0xD0000, +factory, app, factory, 0xe0000, 2200K, +assets_A, data, spiffs, , 700K, diff --git a/partitions/v1/8m.csv b/partitions/v1/8m.csv new file mode 100644 index 0000000..1e0e943 --- /dev/null +++ b/partitions/v1/8m.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +model, data, spiffs, 0x10000, 0xF0000, +ota_0, app, ota_0, 0x100000, 0x380000, +ota_1, app, ota_1, 0x480000, 0x380000, diff --git a/partitions/v2/16m.csv b/partitions/v2/16m.csv new file mode 100644 index 0000000..8af93a3 --- /dev/null +++ b/partitions/v2/16m.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +ota_0, app, ota_0, 0x20000, 0x3f0000, +ota_1, app, ota_1, , 0x3f0000, +assets, data, spiffs, 0x800000, 8M diff --git a/partitions/v2/16m_c3.csv b/partitions/v2/16m_c3.csv new file mode 100644 index 0000000..e444023 --- /dev/null +++ b/partitions/v2/16m_c3.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +ota_0, app, ota_0, 0x20000, 0x3f0000, +ota_1, app, ota_1, , 0x3f0000, +assets, data, spiffs, 0x800000, 4000K diff --git a/partitions/v2/32m.csv b/partitions/v2/32m.csv new file mode 100644 index 0000000..d829cbb --- /dev/null +++ b/partitions/v2/32m.csv @@ -0,0 +1,9 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvsfactory, data, nvs, , 200K, +nvs, data, nvs, , 840K, +otadata, data, ota, , 0x2000, +phy_init, data, phy, , 0x1000, +ota_0, app, ota_0, 0x200000, 4M, +ota_1, app, ota_1, 0x600000, 4M, +assets, data, spiffs, 0xA00000, 16M diff --git a/partitions/v2/4m.csv b/partitions/v2/4m.csv new file mode 100644 index 0000000..0d2ceae --- /dev/null +++ b/partitions/v2/4m.csv @@ -0,0 +1,7 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +factory, app, factory, 0x10000, 0x270000, +assets, data, spiffs, 0x280000, 0x180000, diff --git a/partitions/v2/8m.csv b/partitions/v2/8m.csv new file mode 100644 index 0000000..bae9f15 --- /dev/null +++ b/partitions/v2/8m.csv @@ -0,0 +1,8 @@ +# ESP-IDF Partition Table +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x4000, +otadata, data, ota, 0xd000, 0x2000, +phy_init, data, phy, 0xf000, 0x1000, +ota_0, app, ota_0, 0x20000, 0x2f0000, +ota_1, app, ota_1, , 0x2f0000, +assets, data, spiffs, 0x600000, 2M diff --git a/partitions/v2/README.md b/partitions/v2/README.md new file mode 100644 index 0000000..0b56851 --- /dev/null +++ b/partitions/v2/README.md @@ -0,0 +1,107 @@ +# Version 2 Partition Table + +This version introduces significant improvements over v1 by adding an `assets` partition to support network-loadable content and optimizing partition layouts for different flash sizes. + +## Key Changes from v1 + +### Major Improvements +1. **Added Assets Partition**: New `assets` partition for network-loadable content +2. **Replaced Model Partition**: The old `model` partition (960KB) is replaced with a larger `assets` partition +3. **Optimized App Partitions**: Reduced application partition sizes to accommodate assets +4. **Enhanced Flexibility**: Support for dynamic content updates without reflashing + +### Assets Partition Features +The `assets` partition stores: +- **Wake word models**: Customizable wake word models that can be loaded from the network +- **Theme files**: Complete theming system including: + - Fonts (text and icon fonts) + - Audio effects and sound files + - Background images and UI elements + - Custom emoji packs + - Language configuration files +- **Dynamic Content**: All content can be updated over-the-air via HTTP downloads + +## Partition Layout Comparison + +### v1 Layout (16MB) +- `nvs`: 16KB (non-volatile storage) +- `otadata`: 8KB (OTA data) +- `phy_init`: 4KB (PHY initialization data) +- `model`: 960KB (model storage - fixed content) +- `ota_0`: 6MB (application partition 0) +- `ota_1`: 6MB (application partition 1) + +### v2 Layout (16MB) +- `nvs`: 16KB (non-volatile storage) +- `otadata`: 8KB (OTA data) +- `phy_init`: 4KB (PHY initialization data) +- `ota_0`: 4MB (application partition 0) +- `ota_1`: 4MB (application partition 1) +- `assets`: 8MB (network-loadable assets) + +## Available Configurations + +### 8MB Flash Devices (`8m.csv`) +- `nvs`: 16KB +- `otadata`: 8KB +- `phy_init`: 4KB +- `ota_0`: 3MB +- `ota_1`: 3MB +- `assets`: 2MB + +### 16MB Flash Devices (`16m.csv`) - Standard +- `nvs`: 16KB +- `otadata`: 8KB +- `phy_init`: 4KB +- `ota_0`: 4MB +- `ota_1`: 4MB +- `assets`: 8MB + +### 16MB Flash Devices (`16m_c3.csv`) - ESP32-C3 Optimized +- `nvs`: 16KB +- `otadata`: 8KB +- `phy_init`: 4KB +- `ota_0`: 4MB +- `ota_1`: 4MB +- `assets`: 4MB (4000K - limited by available mmap pages) + +### 32MB Flash Devices (`32m.csv`) +- `nvsfactory`: 200KB +- `nvs`: 840KB +- `otadata`: 8KB +- `phy_init`: 4KB +- `ota_0`: 4MB +- `ota_1`: 4MB +- `assets`: 16MB + +## Benefits + +1. **Dynamic Content Management**: Users can download and update wake word models, themes, and other assets without reflashing the device +2. **Reduced App Size**: Application partitions are optimized, allowing more space for dynamic content +3. **Enhanced Customization**: Support for custom themes, wake words, and language packs enhances user experience +4. **Network Flexibility**: Assets can be updated independently of the main application firmware +5. **Better Resource Utilization**: Efficient use of flash memory with configurable asset storage +6. **OTA Asset Updates**: Assets can be updated over-the-air via HTTP downloads + +## Technical Details + +- **Partition Type**: Assets partition uses `spiffs` subtype for SPIFFS filesystem compatibility +- **Memory Mapping**: Assets are memory-mapped for efficient access during runtime +- **Checksum Validation**: Built-in integrity checking ensures asset data validity +- **Progressive Download**: Assets can be downloaded progressively with progress tracking +- **Fallback Support**: Graceful fallback to default assets if network updates fail + +## Migration from v1 + +When upgrading from v1 to v2: +1. **Backup Important Data**: Ensure any important data in the old `model` partition is backed up +2. **Flash New Partition Table**: Use the appropriate v2 partition table for your flash size +3. **Download Assets**: The device will automatically download required assets on first boot +4. **Verify Functionality**: Ensure all features work correctly with the new partition layout + +## Usage Notes + +- The `assets` partition size varies by configuration to optimize for different flash sizes +- ESP32-C3 devices use a smaller assets partition (4MB) due to limited available mmap pages in the system +- 32MB devices get the largest assets partition (16MB) for maximum content storage +- All partition tables maintain proper alignment for optimal flash performance \ No newline at end of file diff --git a/scripts/Image_Converter/LVGLImage.py b/scripts/Image_Converter/LVGLImage.py new file mode 100644 index 0000000..b2ffbb3 --- /dev/null +++ b/scripts/Image_Converter/LVGLImage.py @@ -0,0 +1,1426 @@ +#!/usr/bin/env python3 +import os +import logging +import argparse +import subprocess +from os import path +from enum import Enum +from typing import List +from pathlib import Path + +try: + import png +except ImportError: + raise ImportError("Need pypng package, do `pip3 install pypng`") + +try: + import lz4.block +except ImportError: + raise ImportError("Need lz4 package, do `pip3 install lz4`") + + +def uint8_t(val) -> bytes: + return val.to_bytes(1, byteorder='little') + + +def uint16_t(val) -> bytes: + return val.to_bytes(2, byteorder='little') + + +def uint24_t(val) -> bytes: + return val.to_bytes(3, byteorder='little') + + +def uint32_t(val) -> bytes: + try: + return val.to_bytes(4, byteorder='little') + except OverflowError: + raise ParameterError(f"overflow: {hex(val)}") + + +def color_pre_multiply(r, g, b, a, background): + bb = background & 0xff + bg = (background >> 8) & 0xff + br = (background >> 16) & 0xff + + return ((r * a + (255 - a) * br) >> 8, (g * a + (255 - a) * bg) >> 8, + (b * a + (255 - a) * bb) >> 8, a) + + +class Error(Exception): + + def __str__(self): + return self.__class__.__name__ + ': ' + ' '.join(self.args) + + +class FormatError(Error): + """ + Problem with input filename format. + BIN filename does not conform to standard lvgl bin image format + """ + + +class ParameterError(Error): + """ + Parameter for LVGL image not correct + """ + + +class PngQuant: + """ + Compress PNG file to 8bit mode using `pngquant` + """ + + def __init__(self, ncolors=256, dither=True, exec_path="") -> None: + executable = path.join(exec_path, "pngquant") + self.cmd = (f"{executable} {'--nofs' if not dither else ''} " + f"{ncolors} --force - < ") + + def convert(self, filename) -> bytes: + if not os.path.isfile(filename): + raise BaseException(f"file not found: {filename}") + + try: + compressed = subprocess.check_output( + f'{self.cmd} "{str(filename)}"', + stderr=subprocess.STDOUT, + shell=True) + except subprocess.CalledProcessError: + raise BaseException( + "cannot find pngquant tool, install it via " + "`sudo apt install pngquant` for debian " + "or `brew install pngquant` for macintosh " + "For windows, you may need to download pngquant.exe from " + "https://pngquant.org/, and put it in your PATH.") + + return compressed + + +class CompressMethod(Enum): + NONE = 0x00 + RLE = 0x01 + LZ4 = 0x02 + + +class ColorFormat(Enum): + UNKNOWN = 0x00 + RAW = 0x01, + RAW_ALPHA = 0x02, + L8 = 0x06 + I1 = 0x07 + I2 = 0x08 + I4 = 0x09 + I8 = 0x0A + A1 = 0x0B + A2 = 0x0C + A4 = 0x0D + A8 = 0x0E + ARGB8888 = 0x10 + XRGB8888 = 0x11 + RGB565 = 0x12 + ARGB8565 = 0x13 + RGB565A8 = 0x14 + RGB888 = 0x0F + + @property + def bpp(self) -> int: + """ + Return bit per pixel for this cf + """ + cf_map = { + ColorFormat.L8: 8, + ColorFormat.I1: 1, + ColorFormat.I2: 2, + ColorFormat.I4: 4, + ColorFormat.I8: 8, + ColorFormat.A1: 1, + ColorFormat.A2: 2, + ColorFormat.A4: 4, + ColorFormat.A8: 8, + ColorFormat.ARGB8888: 32, + ColorFormat.XRGB8888: 32, + ColorFormat.RGB565: 16, + ColorFormat.RGB565A8: 16, # 16bpp + a8 map + ColorFormat.ARGB8565: 24, + ColorFormat.RGB888: 24, + } + + return cf_map[self] if self in cf_map else 0 + + @property + def ncolors(self) -> int: + """ + Return number of colors in palette if cf is indexed1/2/4/8. + Return zero if cf is not indexed format + """ + + cf_map = { + ColorFormat.I1: 2, + ColorFormat.I2: 4, + ColorFormat.I4: 16, + ColorFormat.I8: 256, + } + return cf_map.get(self, 0) + + @property + def is_indexed(self) -> bool: + """ + Return if cf is indexed color format + """ + return self.ncolors != 0 + + @property + def is_alpha_only(self) -> bool: + return ColorFormat.A1.value <= self.value <= ColorFormat.A8.value + + @property + def has_alpha(self) -> bool: + return self.is_alpha_only or self.is_indexed or self in ( + ColorFormat.ARGB8888, + ColorFormat.XRGB8888, # const alpha: 0xff + ColorFormat.ARGB8565, + ColorFormat.RGB565A8) + + @property + def is_colormap(self) -> bool: + return self in (ColorFormat.ARGB8888, ColorFormat.RGB888, + ColorFormat.XRGB8888, ColorFormat.RGB565A8, + ColorFormat.ARGB8565, ColorFormat.RGB565) + + @property + def is_luma_only(self) -> bool: + return self in (ColorFormat.L8, ) + + +def bit_extend(value, bpp): + """ + Extend value from bpp to 8 bit with interpolation to reduce rounding error. + """ + + if value == 0: + return 0 + + res = value + bpp_now = bpp + while bpp_now < 8: + res |= value << (8 - bpp_now) + bpp_now += bpp + + return res + + +def unpack_colors(data: bytes, cf: ColorFormat, w) -> List: + """ + Unpack lvgl 1/2/4/8/16/32 bpp color to png color: alpha map, grey scale, + or R,G,B,(A) map + """ + ret = [] + bpp = cf.bpp + if bpp == 8: + ret = data + elif bpp == 4: + if cf == ColorFormat.A4: + values = [x * 17 for x in range(16)] + else: + values = [x for x in range(16)] + + for p in data: + for i in range(2): + ret.append(values[(p >> (4 - i * 4)) & 0x0f]) + if len(ret) % w == 0: + break + + elif bpp == 2: + if cf == ColorFormat.A2: + values = [x * 85 for x in range(4)] + else: # must be ColorFormat.I2 + values = [x for x in range(4)] + for p in data: + for i in range(4): + ret.append(values[(p >> (6 - i * 2)) & 0x03]) + if len(ret) % w == 0: + break + elif bpp == 1: + if cf == ColorFormat.A1: + values = [0, 255] + else: + values = [0, 1] + for p in data: + for i in range(8): + ret.append(values[(p >> (7 - i)) & 0x01]) + if len(ret) % w == 0: + break + elif bpp == 16: + # This is RGB565 + pixels = [(data[2 * i + 1] << 8) | data[2 * i] + for i in range(len(data) // 2)] + + for p in pixels: + ret.append(bit_extend((p >> 11) & 0x1f, 5)) # R + ret.append(bit_extend((p >> 5) & 0x3f, 6)) # G + ret.append(bit_extend((p >> 0) & 0x1f, 5)) # B + elif bpp == 24: + if cf == ColorFormat.RGB888: + B = data[0::3] + G = data[1::3] + R = data[2::3] + for r, g, b in zip(R, G, B): + ret += [r, g, b] + elif cf == ColorFormat.RGB565A8: + alpha_size = len(data) // 3 + pixel_alpha = data[-alpha_size:] + pixel_data = data[:-alpha_size] + pixels = [(pixel_data[2 * i + 1] << 8) | pixel_data[2 * i] + for i in range(len(pixel_data) // 2)] + + for a, p in zip(pixel_alpha, pixels): + ret.append(bit_extend((p >> 11) & 0x1f, 5)) # R + ret.append(bit_extend((p >> 5) & 0x3f, 6)) # G + ret.append(bit_extend((p >> 0) & 0x1f, 5)) # B + ret.append(a) + elif cf == ColorFormat.ARGB8565: + L = data[0::3] + H = data[1::3] + A = data[2::3] + + for h, l, a in zip(H, L, A): + p = (h << 8) | (l) + ret.append(bit_extend((p >> 11) & 0x1f, 5)) # R + ret.append(bit_extend((p >> 5) & 0x3f, 6)) # G + ret.append(bit_extend((p >> 0) & 0x1f, 5)) # B + ret.append(a) # A + + elif bpp == 32: + B = data[0::4] + G = data[1::4] + R = data[2::4] + A = data[3::4] + for r, g, b, a in zip(R, G, B, A): + ret += [r, g, b, a] + else: + assert 0 + + return ret + + +def write_c_array_file( + w: int, h: int, + stride: int, + cf: ColorFormat, + filename: str, + premultiplied: bool, + compress: CompressMethod, + data: bytes): + varname = path.basename(filename).split('.')[0] + varname = varname.replace("-", "_") + varname = varname.replace(".", "_") + + flags = "0" + if compress is not CompressMethod.NONE: + flags += " | LV_IMAGE_FLAGS_COMPRESSED" + if premultiplied: + flags += " | LV_IMAGE_FLAGS_PREMULTIPLIED" + + macro = "LV_ATTRIBUTE_" + varname.upper() + header = f''' +#if defined(LV_LVGL_H_INCLUDE_SIMPLE) +#include "lvgl.h" +#elif defined(LV_BUILD_TEST) +#include "../lvgl.h" +#else +#include "lvgl/lvgl.h" +#endif + + +#ifndef LV_ATTRIBUTE_MEM_ALIGN +#define LV_ATTRIBUTE_MEM_ALIGN +#endif + +#ifndef {macro} +#define {macro} +#endif + +static const +LV_ATTRIBUTE_MEM_ALIGN LV_ATTRIBUTE_LARGE_CONST {macro} +uint8_t {varname}_map[] = {{ +''' + + ending = f''' +}}; + +const lv_image_dsc_t {varname} = {{ + .header.magic = LV_IMAGE_HEADER_MAGIC, + .header.cf = LV_COLOR_FORMAT_{cf.name}, + .header.flags = {flags}, + .header.w = {w}, + .header.h = {h}, + .header.stride = {stride}, + .data_size = sizeof({varname}_map), + .data = {varname}_map, +}}; + +''' + + def write_binary(f, data, stride): + stride = 16 if stride == 0 else stride + for i, v in enumerate(data): + if i % stride == 0: + f.write("\n ") + f.write(f"0x{v:02x},") + f.write("\n") + + with open(filename, "w+") as f: + f.write(header) + + if compress != CompressMethod.NONE: + write_binary(f, data, 16) + else: + # write palette separately + ncolors = cf.ncolors + if ncolors: + write_binary(f, data[:ncolors * 4], 16) + + write_binary(f, data[ncolors * 4:], stride) + + f.write(ending) + + +class LVGLImageHeader: + + def __init__(self, + cf: ColorFormat = ColorFormat.UNKNOWN, + w: int = 0, + h: int = 0, + stride: int = 0, + align: int = 1, + flags: int = 0): + self.cf = cf + self.flags = flags + self.w = w & 0xffff + self.h = h & 0xffff + if w > 0xffff or h > 0xffff: + raise ParameterError(f"w, h overflow: {w}x{h}") + if align < 1: + # stride align in bytes must be larger than 1 + raise ParameterError(f"Invalid stride align: {align}") + + self.stride = self.stride_align(align) if stride == 0 else stride + + def stride_align(self, align: int) -> int: + stride = self.stride_default + if align == 1: + pass + elif align > 1: + stride = (stride + align - 1) // align + stride *= align + else: + raise ParameterError(f"Invalid stride align: {align}") + + self.stride = stride + return stride + + @property + def stride_default(self) -> int: + return (self.w * self.cf.bpp + 7) // 8 + + @property + def binary(self) -> bytearray: + binary = bytearray() + binary += uint8_t(0x19) # magic number for lvgl version 9 + binary += uint8_t(self.cf.value) + binary += uint16_t(self.flags) # 16bits flags + + binary += uint16_t(self.w) # 16bits width + binary += uint16_t(self.h) # 16bits height + binary += uint16_t(self.stride) # 16bits stride + + binary += uint16_t(0) # 16bits reserved + return binary + + def from_binary(self, data: bytes): + if len(data) < 12: + raise FormatError("invalid header length") + + try: + self.cf = ColorFormat(data[1] & 0x1f) # color format + except ValueError as exc: + raise FormatError(f"invalid color format: {hex(data[0])}") from exc + self.w = int.from_bytes(data[4:6], 'little') + self.h = int.from_bytes(data[6:8], 'little') + self.stride = int.from_bytes(data[8:10], 'little') + return self + + +class LVGLCompressData: + + def __init__(self, + cf: ColorFormat, + method: CompressMethod, + raw_data: bytes = b''): + self.blk_size = (cf.bpp + 7) // 8 + self.compress = method + self.raw_data = raw_data + self.raw_data_len = len(raw_data) + self.compressed = self._compress(raw_data) + + def _compress(self, raw_data: bytes) -> bytearray: + if self.compress == CompressMethod.NONE: + return raw_data + + if self.compress == CompressMethod.RLE: + # RLE compression performs on pixel unit, pad data to pixel unit + pad = b'\x00' * 0 + if self.raw_data_len % self.blk_size: + pad = b'\x00' * (self.blk_size - self.raw_data_len % self.blk_size) + compressed = RLEImage().rle_compress(raw_data + pad, self.blk_size) + elif self.compress == CompressMethod.LZ4: + compressed = lz4.block.compress(raw_data, store_size=False) + else: + raise ParameterError(f"Invalid compress method: {self.compress}") + + self.compressed_len = len(compressed) + + bin = bytearray() + bin += uint32_t(self.compress.value) + bin += uint32_t(self.compressed_len) + bin += uint32_t(self.raw_data_len) + bin += compressed + return bin + + +class LVGLImage: + + def __init__(self, + cf: ColorFormat = ColorFormat.UNKNOWN, + w: int = 0, + h: int = 0, + data: bytes = b'') -> None: + self.stride = 0 # default no valid stride value + self.premultiplied = False + self.rgb565_dither = False + self.set_data(cf, w, h, data) + + def __repr__(self) -> str: + return (f"'LVGL image {self.w}x{self.h}, {self.cf.name}, " + f"{'Pre-multiplied, ' if self.premultiplied else ''}" + f"stride: {self.stride} " + f"(12+{self.data_len})Byte'") + + def adjust_stride(self, stride: int = 0, align: int = 1): + """ + Stride can be set directly, or by stride alignment in bytes + """ + if self.stride == 0: + # stride can only be 0, when LVGLImage is created with empty data + logging.warning("Cannot adjust stride for empty image") + return + + if align >= 1 and stride == 0: + # The header with specified stride alignment + header = LVGLImageHeader(self.cf, self.w, self.h, align=align) + stride = header.stride + elif stride > 0: + pass + else: + raise ParameterError(f"Invalid parameter, align:{align}," + f" stride:{stride}") + + if self.stride == stride: + return # no stride adjustment + + # if current image is empty, no need to do anything + if self.data_len == 0: + self.stride = 0 + return + + current = LVGLImageHeader(self.cf, self.w, self.h, stride=self.stride) + + if stride < current.stride_default: + raise ParameterError(f"Stride is too small:{stride}, " + f"minimal:{current.stride_default}") + + def change_stride(data: bytearray, h, current_stride, new_stride): + data_in = data + data_out = [] # stride adjusted new data + if new_stride < current_stride: # remove padding byte + for i in range(h): + start = i * current_stride + end = start + new_stride + data_out.append(data_in[start:end]) + else: # adding more padding bytes + padding = b'\x00' * (new_stride - current_stride) + for i in range(h): + data_out.append(data_in[i * current_stride:(i + 1) * + current_stride]) + data_out.append(padding) + return b''.join(data_out) + + palette_size = self.cf.ncolors * 4 + data_out = [self.data[:palette_size]] + data_out.append( + change_stride(self.data[palette_size:], self.h, current.stride, + stride)) + + # deal with alpha map for RGB565A8 + if self.cf == ColorFormat.RGB565A8: + logging.warning("handle RGB565A8 alpha map") + a8_stride = self.stride // 2 + a8_map = self.data[-a8_stride * self.h:] + data_out.append( + change_stride(a8_map, self.h, current.stride // 2, + stride // 2)) + + self.stride = stride + self.data = bytearray(b''.join(data_out)) + + def premultiply(self): + """ + Pre-multiply image RGB data with alpha, set corresponding image header flags + """ + if self.premultiplied: + raise ParameterError("Image already pre-multiplied") + + if not self.cf.has_alpha: + raise ParameterError(f"Image has no alpha channel: {self.cf.name}") + + if self.cf.is_indexed: + + def multiply(r, g, b, a): + r, g, b = (r * a) >> 8, (g * a) >> 8, (b * a) >> 8 + return uint8_t(b) + uint8_t(g) + uint8_t(r) + uint8_t(a) + + # process the palette only. + palette_size = self.cf.ncolors * 4 + palette = self.data[:palette_size] + palette = [ + multiply(palette[i], palette[i + 1], palette[i + 2], + palette[i + 3]) for i in range(0, len(palette), 4) + ] + palette = b''.join(palette) + self.data = palette + self.data[palette_size:] + elif self.cf is ColorFormat.ARGB8888: + + def multiply(b, g, r, a): + r, g, b = (r * a) >> 8, (g * a) >> 8, (b * a) >> 8 + return uint32_t((a << 24) | (r << 16) | (g << 8) | (b << 0)) + + line_width = self.w * 4 + for h in range(self.h): + offset = h * self.stride + map = self.data[offset:offset + self.stride] + + processed = b''.join([ + multiply(map[i], map[i + 1], map[i + 2], map[i + 3]) + for i in range(0, line_width, 4) + ]) + self.data[offset:offset + line_width] = processed + elif self.cf is ColorFormat.RGB565A8: + + def multiply(data, a): + r = (data >> 11) & 0x1f + g = (data >> 5) & 0x3f + b = (data >> 0) & 0x1f + + r, g, b = (r * a) // 255, (g * a) // 255, (b * a) // 255 + return uint16_t((r << 11) | (g << 5) | (b << 0)) + + line_width = self.w * 2 + for h in range(self.h): + # alpha map offset for this line + offset = self.h * self.stride + h * (self.stride // 2) + a = self.data[offset:offset + self.stride // 2] + + # RGB map offset + offset = h * self.stride + rgb = self.data[offset:offset + self.stride] + + processed = b''.join([ + multiply((rgb[i + 1] << 8) | rgb[i], a[i // 2]) + for i in range(0, line_width, 2) + ]) + self.data[offset:offset + line_width] = processed + elif self.cf is ColorFormat.ARGB8565: + + def multiply(data, a): + r = (data >> 11) & 0x1f + g = (data >> 5) & 0x3f + b = (data >> 0) & 0x1f + + r, g, b = (r * a) // 255, (g * a) // 255, (b * a) // 255 + return uint24_t((a << 16) | (r << 11) | (g << 5) | (b << 0)) + + line_width = self.w * 3 + for h in range(self.h): + offset = h * self.stride + map = self.data[offset:offset + self.stride] + + processed = b''.join([ + multiply((map[i + 1] << 8) | map[i], map[i + 2]) + for i in range(0, line_width, 3) + ]) + self.data[offset:offset + line_width] = processed + else: + raise ParameterError(f"Not supported yet: {self.cf.name}") + + self.premultiplied = True + + @property + def data_len(self) -> int: + """ + Return data_len in byte of this image, excluding image header + """ + + # palette is always in ARGB format, 4Byte per color + p = self.cf.ncolors * 4 if self.is_indexed and self.w * self.h else 0 + p += self.stride * self.h + if self.cf is ColorFormat.RGB565A8: + a8_stride = self.stride // 2 + p += a8_stride * self.h + return p + + @property + def header(self) -> bytearray: + return LVGLImageHeader(self.cf, self.w, self.h) + + @property + def is_indexed(self): + return self.cf.is_indexed + + def set_data(self, + cf: ColorFormat, + w: int, + h: int, + data: bytes, + stride: int = 0): + """ + Directly set LVGL image parameters + """ + + if w > 0xffff or h > 0xffff: + raise ParameterError(f"w, h overflow: {w}x{h}") + + self.cf = cf + self.w = w + self.h = h + + # if stride is 0, then it's aligned to 1byte by default, + # let image header handle it + self.stride = LVGLImageHeader(cf, w, h, stride, align=1).stride + + if self.data_len != len(data): + raise ParameterError(f"{self} data length error got: {len(data)}, " + f"expect: {self.data_len}, {self}") + + self.data = data + + return self + + def from_data(self, data: bytes): + header = LVGLImageHeader().from_binary(data) + return self.set_data(header.cf, header.w, header.h, + data[len(header.binary):], header.stride) + + def from_bin(self, filename: str): + """ + Read from existing bin file and update image parameters + """ + + if not filename.endswith(".bin"): + raise FormatError("filename not ended with '.bin'") + + with open(filename, "rb") as f: + data = f.read() + return self.from_data(data) + + def _check_ext(self, filename: str, ext): + if not filename.lower().endswith(ext): + raise FormatError(f"filename not ended with {ext}") + + def _check_dir(self, filename: str): + dir = path.dirname(filename) + if dir and not path.exists(dir): + logging.info(f"mkdir of {dir} for {filename}") + os.makedirs(dir) + + def to_bin(self, + filename: str, + compress: CompressMethod = CompressMethod.NONE): + """ + Write this image to file, filename should be ended with '.bin' + """ + self._check_ext(filename, ".bin") + self._check_dir(filename) + + with open(filename, "wb+") as f: + bin = bytearray() + flags = 0 + flags |= 0x08 if compress != CompressMethod.NONE else 0 + flags |= 0x01 if self.premultiplied else 0 + + header = LVGLImageHeader(self.cf, + self.w, + self.h, + self.stride, + flags=flags) + bin += header.binary + compressed = LVGLCompressData(self.cf, compress, self.data) + bin += compressed.compressed + + f.write(bin) + + return self + + def to_c_array(self, + filename: str, + compress: CompressMethod = CompressMethod.NONE): + self._check_ext(filename, ".c") + self._check_dir(filename) + + if compress != CompressMethod.NONE: + data = LVGLCompressData(self.cf, compress, self.data).compressed + else: + data = self.data + write_c_array_file(self.w, self.h, self.stride, self.cf, filename, + self.premultiplied, + compress, data) + + def to_png(self, filename: str): + self._check_ext(filename, ".png") + self._check_dir(filename) + + old_stride = self.stride + self.adjust_stride(align=1) + if self.cf.is_indexed: + data = self.data + # Separate lvgl bin image data to palette and bitmap + # The palette is in format of [(RGBA), (RGBA)...]. + # LVGL palette is in format of B,G,R,A,... + palette = [(data[i * 4 + 2], data[i * 4 + 1], data[i * 4 + 0], + data[i * 4 + 3]) for i in range(self.cf.ncolors)] + + data = data[self.cf.ncolors * 4:] + + encoder = png.Writer(self.w, + self.h, + palette=palette, + bitdepth=self.cf.bpp) + # separate packed data to plain data + data = unpack_colors(data, self.cf, self.w) + elif self.cf.is_alpha_only: + # separate packed data to plain data + transparency = unpack_colors(self.data, self.cf, self.w) + data = [] + for a in transparency: + data += [0, 0, 0, a] + encoder = png.Writer(self.w, self.h, greyscale=False, alpha=True) + elif self.cf == ColorFormat.L8: + # to grayscale + encoder = png.Writer(self.w, + self.h, + bitdepth=self.cf.bpp, + greyscale=True, + alpha=False) + data = self.data + elif self.cf.is_colormap: + encoder = png.Writer(self.w, + self.h, + alpha=self.cf.has_alpha, + greyscale=False) + data = unpack_colors(self.data, self.cf, self.w) + else: + logging.warning(f"missing logic: {self.cf.name}") + return + + with open(filename, "wb") as f: + encoder.write_array(f, data) + + self.adjust_stride(stride=old_stride) + + def from_png(self, + filename: str, + cf: ColorFormat = None, + background: int = 0x00_00_00, + rgb565_dither=False): + """ + Create lvgl image from png file. + If cf is none, used I1/2/4/8 based on palette size + """ + + self.background = background + self.rgb565_dither = rgb565_dither + + if cf is None: # guess cf from filename + # split filename string and match with ColorFormat to check + # which cf to use + names = str(path.basename(filename)).split(".") + for c in names[1:-1]: + if c in ColorFormat.__members__: + cf = ColorFormat[c] + break + + if cf is None or cf.is_indexed: # palette mode + self._png_to_indexed(cf, filename) + elif cf.is_alpha_only: + self._png_to_alpha_only(cf, filename) + elif cf.is_luma_only: + self._png_to_luma_only(cf, filename) + elif cf.is_colormap: + self._png_to_colormap(cf, filename) + else: + logging.warning(f"missing logic: {cf.name}") + + logging.info(f"from png: {filename}, cf: {self.cf.name}") + return self + + def _png_to_indexed(self, cf: ColorFormat, filename: str): + # convert to palette mode + auto_cf = cf is None + + # read the image data to get the metadata + reader = png.Reader(filename=filename) + w, h, rows, metadata = reader.read() + + # to preserve original palette data only convert the image if needed. For this + # check if image has a palette and the requested palette size equals the existing one + if not 'palette' in metadata or not auto_cf and len(metadata['palette']) != 2 ** cf.bpp: + # reread and convert file + reader = png.Reader( + bytes=PngQuant(256 if auto_cf else cf.ncolors).convert(filename)) + w, h, rows, _ = reader.read() + + palette = reader.palette(alpha="force") # always return alpha + + palette_len = len(palette) + if auto_cf: + if palette_len <= 2: + cf = ColorFormat.I1 + elif palette_len <= 4: + cf = ColorFormat.I2 + elif palette_len <= 16: + cf = ColorFormat.I4 + else: + cf = ColorFormat.I8 + + if palette_len != cf.ncolors: + if not auto_cf: + logging.warning( + f"{path.basename(filename)} palette: {palette_len}, " + f"extended to: {cf.ncolors}") + palette += [(255, 255, 255, 0)] * (cf.ncolors - palette_len) + + # Assemble lvgl image palette from PNG palette. + # PNG palette is a list of tuple(R,G,B,A) + + rawdata = bytearray() + for (r, g, b, a) in palette: + rawdata += uint32_t((a << 24) | (r << 16) | (g << 8) | (b << 0)) + + # pack data if not in I8 format + if cf == ColorFormat.I8: + for e in rows: + rawdata += e + else: + for e in png.pack_rows(rows, cf.bpp): + rawdata += e + + self.set_data(cf, w, h, rawdata) + + def _png_to_alpha_only(self, cf: ColorFormat, filename: str): + reader = png.Reader(str(filename)) + w, h, rows, info = reader.asRGBA8() + if not info['alpha']: + raise FormatError(f"{filename} has no alpha channel") + + rawdata = bytearray() + if cf == ColorFormat.A8: + for row in rows: + A = row[3::4] + for e in A: + rawdata += uint8_t(e) + else: + shift = 8 - cf.bpp + mask = 2**cf.bpp - 1 + rows = [[(a >> shift) & mask for a in row[3::4]] for row in rows] + for row in png.pack_rows(rows, cf.bpp): + rawdata += row + + self.set_data(cf, w, h, rawdata) + + def sRGB_to_linear(self, x): + if x < 0.04045: + return x / 12.92 + return pow((x + 0.055) / 1.055, 2.4) + + def linear_to_sRGB(self, y): + if y <= 0.0031308: + return 12.92 * y + return 1.055 * pow(y, 1 / 2.4) - 0.055 + + def _png_to_luma_only(self, cf: ColorFormat, filename: str): + reader = png.Reader(str(filename)) + w, h, rows, info = reader.asRGBA8() + rawdata = bytearray() + for row in rows: + R = row[0::4] + G = row[1::4] + B = row[2::4] + A = row[3::4] + for r, g, b, a in zip(R, G, B, A): + r, g, b, a = color_pre_multiply(r, g, b, a, self.background) + r = self.sRGB_to_linear(r / 255.0) + g = self.sRGB_to_linear(g / 255.0) + b = self.sRGB_to_linear(b / 255.0) + luma = 0.2126 * r + 0.7152 * g + 0.0722 * b + rawdata += uint8_t(int(self.linear_to_sRGB(luma) * 255)) + + self.set_data(ColorFormat.L8, w, h, rawdata) + + def _png_to_colormap(self, cf, filename: str): + + if cf == ColorFormat.ARGB8888: + + def pack(r, g, b, a): + return uint32_t((a << 24) | (r << 16) | (g << 8) | (b << 0)) + elif cf == ColorFormat.XRGB8888: + + def pack(r, g, b, a): + r, g, b, a = color_pre_multiply(r, g, b, a, self.background) + return uint32_t((0xff << 24) | (r << 16) | (g << 8) | (b << 0)) + elif cf == ColorFormat.RGB888: + + def pack(r, g, b, a): + r, g, b, a = color_pre_multiply(r, g, b, a, self.background) + return uint24_t((r << 16) | (g << 8) | (b << 0)) + elif cf == ColorFormat.RGB565: + + def pack(r, g, b, a): + r, g, b, a = color_pre_multiply(r, g, b, a, self.background) + color = (r >> 3) << 11 + color |= (g >> 2) << 5 + color |= (b >> 3) << 0 + return uint16_t(color) + + elif cf == ColorFormat.RGB565A8: + + def pack(r, g, b, a): + color = (r >> 3) << 11 + color |= (g >> 2) << 5 + color |= (b >> 3) << 0 + return uint16_t(color) + elif cf == ColorFormat.ARGB8565: + + def pack(r, g, b, a): + color = (r >> 3) << 11 + color |= (g >> 2) << 5 + color |= (b >> 3) << 0 + return uint24_t((a << 16) | color) + else: + raise FormatError(f"Invalid color format: {cf.name}") + + reader = png.Reader(str(filename)) + w, h, rows, _ = reader.asRGBA8() + rawdata = bytearray() + alpha = bytearray() + for y, row in enumerate(rows): + R = row[0::4] + G = row[1::4] + B = row[2::4] + A = row[3::4] + for x, (r, g, b, a) in enumerate(zip(R, G, B, A)): + if cf == ColorFormat.RGB565A8: + alpha += uint8_t(a) + + if ( + self.rgb565_dither and + cf in (ColorFormat.RGB565, ColorFormat.RGB565A8, ColorFormat.ARGB8565) + ): + treshold_id = ((y & 7) << 3) + (x & 7) + + r = min(r + red_thresh[treshold_id], 0xFF) & 0xF8 + g = min(g + green_thresh[treshold_id], 0xFF) & 0xFC + b = min(b + blue_thresh[treshold_id], 0xFF) & 0xF8 + + rawdata += pack(r, g, b, a) + + if cf == ColorFormat.RGB565A8: + rawdata += alpha + + self.set_data(cf, w, h, rawdata) + + +red_thresh = [ + 1, 7, 3, 5, 0, 8, 2, 6, + 7, 1, 5, 3, 8, 0, 6, 2, + 3, 5, 0, 8, 2, 6, 1, 7, + 5, 3, 8, 0, 6, 2, 7, 1, + 0, 8, 2, 6, 1, 7, 3, 5, + 8, 0, 6, 2, 7, 1, 5, 3, + 2, 6, 1, 7, 3, 5, 0, 8, + 6, 2, 7, 1, 5, 3, 8, 0 +] + +green_thresh = [ + 1, 3, 2, 2, 3, 1, 2, 2, + 2, 2, 0, 4, 2, 2, 4, 0, + 3, 1, 2, 2, 1, 3, 2, 2, + 2, 2, 4, 0, 2, 2, 0, 4, + 1, 3, 2, 2, 3, 1, 2, 2, + 2, 2, 0, 4, 2, 2, 4, 0, + 3, 1, 2, 2, 1, 3, 2, 2, + 2, 2, 4, 0, 2, 2, 0, 4 +] + +blue_thresh = [ + 5, 3, 8, 0, 6, 2, 7, 1, + 3, 5, 0, 8, 2, 6, 1, 7, + 8, 0, 6, 2, 7, 1, 5, 3, + 0, 8, 2, 6, 1, 7, 3, 5, + 6, 2, 7, 1, 5, 3, 8, 0, + 2, 6, 1, 7, 3, 5, 0, 8, + 7, 1, 5, 3, 8, 0, 6, 2, + 1, 7, 3, 5, 0, 8, 2, 6 +] + + +class RLEHeader: + + def __init__(self, blksize: int, len: int): + self.blksize = blksize + self.len = len + + @property + def binary(self): + magic = 0x5aa521e0 + + rle_header = self.blksize + rle_header |= (self.len & 0xffffff) << 4 + + binary = bytearray() + binary.extend(uint32_t(magic)) + binary.extend(uint32_t(rle_header)) + return binary + + +class RLEImage(LVGLImage): + + def __init__(self, + cf: ColorFormat = ColorFormat.UNKNOWN, + w: int = 0, + h: int = 0, + data: bytes = b'') -> None: + super().__init__(cf, w, h, data) + + def to_rle(self, filename: str): + """ + Compress this image to file, filename should be ended with '.rle' + """ + self._check_ext(filename, ".rle") + self._check_dir(filename) + + # compress image data excluding lvgl image header + blksize = (self.cf.bpp + 7) // 8 + compressed = self.rle_compress(self.data, blksize) + with open(filename, "wb+") as f: + header = RLEHeader(blksize, len(self.data)).binary + header.extend(self.header.binary) + f.write(header) + f.write(compressed) + + def rle_compress(self, data: bytearray, blksize: int, threshold=16): + index = 0 + data_len = len(data) + compressed_data = [] + memview = memoryview(data) + while index < data_len: + repeat_cnt = self.get_repeat_count(memview[index:], blksize) + if repeat_cnt == 0: + # done + break + elif repeat_cnt < threshold: + nonrepeat_cnt = self.get_nonrepeat_count( + memview[index:], blksize, threshold) + ctrl_byte = uint8_t(nonrepeat_cnt | 0x80) + compressed_data.append(ctrl_byte) + compressed_data.append(memview[index:index + + nonrepeat_cnt * blksize]) + index += nonrepeat_cnt * blksize + else: + ctrl_byte = uint8_t(repeat_cnt) + compressed_data.append(ctrl_byte) + compressed_data.append(memview[index:index + blksize]) + index += repeat_cnt * blksize + + return b"".join(compressed_data) + + def get_repeat_count(self, data: bytearray, blksize: int): + if len(data) < blksize: + return 0 + + start = data[:blksize] + index = 0 + repeat_cnt = 0 + value = 0 + + while index < len(data): + value = data[index:index + blksize] + + if value == start: + repeat_cnt += 1 + if repeat_cnt == 127: # limit max repeat count to max value of signed char. + break + else: + break + index += blksize + + return repeat_cnt + + def get_nonrepeat_count(self, data: bytearray, blksize: int, threshold): + if len(data) < blksize: + return 0 + + pre_value = data[:blksize] + + index = 0 + nonrepeat_count = 0 + + repeat_cnt = 0 + while True: + value = data[index:index + blksize] + if value == pre_value: + repeat_cnt += 1 + if repeat_cnt > threshold: + # repeat found. + break + else: + pre_value = value + nonrepeat_count += 1 + repeat_cnt + repeat_cnt = 0 + if nonrepeat_count >= 127: # limit max repeat count to max value of signed char. + nonrepeat_count = 127 + break + + index += blksize # move to next position + if index >= len(data): # data end + nonrepeat_count += repeat_cnt + break + + return nonrepeat_count + + +class RAWImage(): + ''' + RAW image is an exception to LVGL image, it has color format of RAW or RAW_ALPHA. + It has same image header as LVGL image, but the data is pure raw data from file. + It does not support stride adjustment etc. features for LVGL image. + It only supports convert an image to C array with RAW or RAW_ALPHA format. + ''' + CF_SUPPORTED = (ColorFormat.RAW, ColorFormat.RAW_ALPHA) + + class NotSupported(NotImplementedError): + pass + + def __init__(self, + cf: ColorFormat = ColorFormat.UNKNOWN, + data: bytes = b'') -> None: + self.cf = cf + self.data = data + + def to_c_array(self, + filename: str): + # Image size is set to zero, to let PNG or JPEG decoder to handle it + # Stride is meaningless for RAW image + write_c_array_file(0, 0, 0, self.cf, filename, + False, CompressMethod.NONE, self.data) + + def from_file(self, + filename: str, + cf: ColorFormat = None): + if cf not in RAWImage.CF_SUPPORTED: + raise RAWImage.NotSupported(f"Invalid color format: {cf.name}") + + with open(filename, "rb") as f: + self.data = f.read() + self.cf = cf + return self + + +class OutputFormat(Enum): + C_ARRAY = "C" + BIN_FILE = "BIN" + PNG_FILE = "PNG" # convert to lvgl image and then to png + + +class PNGConverter: + + def __init__(self, + files: List, + cf: ColorFormat, + ofmt: OutputFormat, + odir: str, + background: int = 0x00, + align: int = 1, + premultiply: bool = False, + compress: CompressMethod = CompressMethod.NONE, + keep_folder=True, + rgb565_dither=False) -> None: + self.files = files + self.cf = cf + self.ofmt = ofmt + self.output = odir + self.pngquant = None + self.keep_folder = keep_folder + self.align = align + self.premultiply = premultiply + self.compress = compress + self.background = background + self.rgb565_dither = rgb565_dither + + def _replace_ext(self, input, ext): + if self.keep_folder: + name, _ = path.splitext(input) + else: + name, _ = path.splitext(path.basename(input)) + output = name + ext + output = path.join(self.output, output) + return output + + def convert(self): + output = [] + for f in self.files: + if self.cf in (ColorFormat.RAW, ColorFormat.RAW_ALPHA): + # Process RAW image explicitly + img = RAWImage().from_file(f, self.cf) + img.to_c_array(self._replace_ext(f, ".c")) + else: + img = LVGLImage().from_png(f, self.cf, background=self.background, rgb565_dither=self.rgb565_dither) + img.adjust_stride(align=self.align) + + if self.premultiply: + img.premultiply() + output.append((f, img)) + if self.ofmt == OutputFormat.BIN_FILE: + img.to_bin(self._replace_ext(f, ".bin"), + compress=self.compress) + elif self.ofmt == OutputFormat.C_ARRAY: + img.to_c_array(self._replace_ext(f, ".c"), + compress=self.compress) + elif self.ofmt == OutputFormat.PNG_FILE: + img.to_png(self._replace_ext(f, ".png")) + + return output + + +def main(): + parser = argparse.ArgumentParser(description='LVGL PNG to bin image tool.') + parser.add_argument('--ofmt', + help="output filename format, C or BIN", + default="BIN", + choices=["C", "BIN", "PNG"]) + parser.add_argument( + '--cf', + help=("bin image color format, use AUTO for automatically " + "choose from I1/2/4/8"), + default="I8", + choices=[ + "L8", "I1", "I2", "I4", "I8", "A1", "A2", "A4", "A8", "ARGB8888", + "XRGB8888", "RGB565", "RGB565A8", "ARGB8565", "RGB888", "AUTO", + "RAW", "RAW_ALPHA" + ]) + + parser.add_argument('--rgb565dither', action='store_true', + help="use dithering to correct banding in gradients", default=False) + + parser.add_argument('--premultiply', action='store_true', + help="pre-multiply color with alpha", default=False) + + parser.add_argument('--compress', + help=("Binary data compress method, default to NONE"), + default="NONE", + choices=["NONE", "RLE", "LZ4"]) + + parser.add_argument('--align', + help="stride alignment in bytes for bin image", + default=1, + type=int, + metavar='byte', + nargs='?') + parser.add_argument('--background', + help="Background color for formats without alpha", + default=0x00_00_00, + type=lambda x: int(x, 0), + metavar='color', + nargs='?') + parser.add_argument('-o', + '--output', + default="./output", + help="Select the output folder, default to ./output") + parser.add_argument('-v', '--verbose', action='store_true') + parser.add_argument( + 'input', help="the filename or folder to be recursively converted") + + args = parser.parse_args() + + if path.isfile(args.input): + files = [args.input] + elif path.isdir(args.input): + files = list(Path(args.input).rglob("*.[pP][nN][gG]")) + else: + raise BaseException(f"invalid input: {args.input}") + + if args.verbose: + logging.basicConfig(level=logging.INFO) + + logging.info(f"options: {args.__dict__}, files:{[str(f) for f in files]}") + + if args.cf == "AUTO": + cf = None + else: + cf = ColorFormat[args.cf] + + ofmt = OutputFormat(args.ofmt) if cf not in ( + ColorFormat.RAW, ColorFormat.RAW_ALPHA) else OutputFormat.C_ARRAY + compress = CompressMethod[args.compress] + + converter = PNGConverter(files, + cf, + ofmt, + args.output, + background=args.background, + align=args.align, + premultiply=args.premultiply, + compress=compress, + keep_folder=False, + rgb565_dither=args.rgb565dither) + output = converter.convert() + for f, img in output: + logging.info(f"len: {img.data_len} for {path.basename(f)} ") + + print(f"done {len(files)} files") + + +def test(): + logging.basicConfig(level=logging.INFO) + f = "pngs/cogwheel.RGB565A8.png" + img = LVGLImage().from_png(f, + cf=ColorFormat.ARGB8565, + background=0xFF_FF_00, + rgb565_dither=True) + img.adjust_stride(align=16) + img.premultiply() + img.to_bin("output/cogwheel.ARGB8565.bin") + img.to_c_array("output/cogwheel-abc.c") # file name is used as c var name + img.to_png("output/cogwheel.ARGB8565.png.png") # convert back to png + + +def test_raw(): + logging.basicConfig(level=logging.INFO) + f = "pngs/cogwheel.RGB565A8.png" + img = RAWImage().from_file(f, + cf=ColorFormat.RAW_ALPHA) + img.to_c_array("output/cogwheel-raw.c") + + +if __name__ == "__main__": + # test() + # test_raw() + main() diff --git a/scripts/Image_Converter/README.md b/scripts/Image_Converter/README.md new file mode 100644 index 0000000..62a02cd --- /dev/null +++ b/scripts/Image_Converter/README.md @@ -0,0 +1,45 @@ +# LVGL图片转换工具 + +这个目录包含两个用于处理和转换图片为LVGL格式的Python脚本: + +## 1. LVGLImage (LVGLImage.py) + +引用自LVGL[官方repo](https://github.com/lvgl/lvgl)的转换脚本[LVGLImage.py](https://github.com/lvgl/lvgl/blob/master/scripts/LVGLImage.py) + +## 2. LVGL图片转换工具 (lvgl_tools_gui.py) + +调用`LVGLImage.py`,将图片批量转换为LVGL图片格式 +可用于修改小智的默认表情,具体修改教程[在这里](https://www.bilibili.com/video/BV12FQkYeEJ3/) + +### 特性 + +- 图形化操作,界面更友好 +- 支持批量转换图片 +- 自动识别图片格式并选择最佳的颜色格式转换 +- 多分辨率支持 + +### 使用方法 + +创建虚拟环境 +```bash +# 创建 venv +python -m venv venv +# 激活环境 +source venv/bin/activate # Linux/Mac +venv\Scripts\activate # Windows +``` + +安装依赖 +```bash +pip install -r requirements.txt +``` + +运行转换工具 + +```bash +# 激活环境 +source venv/bin/activate # Linux/Mac +venv\Scripts\activate # Windows +# 运行 +python lvgl_tools_gui.py +``` diff --git a/scripts/Image_Converter/lvgl_tools_gui.py b/scripts/Image_Converter/lvgl_tools_gui.py new file mode 100644 index 0000000..de7c1f2 --- /dev/null +++ b/scripts/Image_Converter/lvgl_tools_gui.py @@ -0,0 +1,253 @@ +import tkinter as tk +from tkinter import ttk, filedialog, messagebox +from PIL import Image +import os +import tempfile +import sys +from LVGLImage import LVGLImage, ColorFormat, CompressMethod + +HELP_TEXT = """LVGL图片转换工具使用说明: + +1. 添加文件:点击“添加文件”按钮选择需要转换的图片,支持批量导入 + +2. 移除文件:在列表中选中文件前的复选框“[ ]”(选中后会变成“[√]”),点击“移除选中”可删除选定文件 + +3. 设置分辨率:选择需要的分辨率,如128x128 + 建议根据自己的设备的屏幕分辨率来选择。过大和过小都会影响显示效果。 + +4. 颜色格式:选择“自动识别”会根据图片是否透明自动选择,或手动指定 + 除非你了解这个选项,否则建议使用自动识别,不然可能会出现一些意想不到的问题…… + +5. 压缩方式:选择NONE或RLE压缩 + 除非你了解这个选项,否则建议保持默认NONE不压缩 + +6. 输出目录:设置转换后文件的保存路径 + 默认为程序所在目录下的output文件夹 + +7. 转换:点击“转换全部”或“转换选中”开始转换 +""" + +class ImageConverterApp: + def __init__(self, root): + self.root = root + self.root.title("LVGL图片转换工具") + self.root.geometry("750x650") + + # 初始化变量 + self.output_dir = tk.StringVar(value=os.path.abspath("output")) + self.resolution = tk.StringVar(value="128x128") + self.color_format = tk.StringVar(value="自动识别") + self.compress_method = tk.StringVar(value="NONE") + + # 创建UI组件 + self.create_widgets() + self.redirect_output() + + def create_widgets(self): + # 参数设置框架 + settings_frame = ttk.LabelFrame(self.root, text="转换设置") + settings_frame.grid(row=0, column=0, padx=10, pady=5, sticky="ew") + + # 分辨率设置 + ttk.Label(settings_frame, text="分辨率:").grid(row=0, column=0, padx=2) + ttk.Combobox(settings_frame, textvariable=self.resolution, + values=["512x512", "256x256", "128x128", "64x64", "32x32"], width=8).grid(row=0, column=1, padx=2) + + # 颜色格式 + ttk.Label(settings_frame, text="颜色格式:").grid(row=0, column=2, padx=2) + ttk.Combobox(settings_frame, textvariable=self.color_format, + values=["自动识别", "RGB565", "RGB565A8"], width=10).grid(row=0, column=3, padx=2) + + # 压缩方式 + ttk.Label(settings_frame, text="压缩方式:").grid(row=0, column=4, padx=2) + ttk.Combobox(settings_frame, textvariable=self.compress_method, + values=["NONE", "RLE"], width=8).grid(row=0, column=5, padx=2) + + # 文件操作框架 + file_frame = ttk.LabelFrame(self.root, text="选取文件") + file_frame.grid(row=1, column=0, padx=10, pady=5, sticky="nsew") + + # 文件操作按钮 + btn_frame = ttk.Frame(file_frame) + btn_frame.pack(fill=tk.X, pady=2) + ttk.Button(btn_frame, text="添加文件", command=self.select_files).pack(side=tk.LEFT, padx=2) + ttk.Button(btn_frame, text="移除选中", command=self.remove_selected).pack(side=tk.LEFT, padx=2) + ttk.Button(btn_frame, text="清空列表", command=self.clear_files).pack(side=tk.LEFT, padx=2) + + # 文件列表(Treeview) + self.tree = ttk.Treeview(file_frame, columns=("selected", "filename"), + show="headings", height=10) + self.tree.heading("selected", text="选择", anchor=tk.W) + self.tree.heading("filename", text="文件名", anchor=tk.W) + self.tree.column("selected", width=60, anchor=tk.W) + self.tree.column("filename", width=600, anchor=tk.W) + self.tree.pack(fill=tk.BOTH, expand=True) + self.tree.bind("", self.on_tree_click) + + # 输出目录 + output_frame = ttk.LabelFrame(self.root, text="输出目录") + output_frame.grid(row=2, column=0, padx=10, pady=5, sticky="ew") + ttk.Entry(output_frame, textvariable=self.output_dir, width=60).pack(side=tk.LEFT, padx=5) + ttk.Button(output_frame, text="浏览", command=self.select_output_dir).pack(side=tk.RIGHT, padx=5) + + # 转换按钮和帮助按钮 + convert_frame = ttk.Frame(self.root) + convert_frame.grid(row=3, column=0, padx=10, pady=10) + ttk.Button(convert_frame, text="转换全部文件", command=lambda: self.start_conversion(True)).pack(side=tk.LEFT, padx=5) + ttk.Button(convert_frame, text="转换选中文件", command=lambda: self.start_conversion(False)).pack(side=tk.LEFT, padx=5) + ttk.Button(convert_frame, text="帮助", command=self.show_help).pack(side=tk.RIGHT, padx=5) + + # 日志区域(新增清空按钮部分) + log_frame = ttk.LabelFrame(self.root, text="日志") + log_frame.grid(row=4, column=0, padx=10, pady=5, sticky="nsew") + + # 添加按钮框架 + log_btn_frame = ttk.Frame(log_frame) + log_btn_frame.pack(fill=tk.X, side=tk.BOTTOM) + + # 清空日志按钮 + ttk.Button(log_btn_frame, text="清空日志", command=self.clear_log).pack(side=tk.RIGHT, padx=5, pady=2) + + self.log_text = tk.Text(log_frame, height=15) + self.log_text.pack(fill=tk.BOTH, expand=True) + + # 布局配置 + self.root.columnconfigure(0, weight=1) + self.root.rowconfigure(1, weight=1) + self.root.rowconfigure(4, weight=1) + + def clear_log(self): + """清空日志内容""" + self.log_text.delete(1.0, tk.END) + + def show_help(self): + messagebox.showinfo("帮助", HELP_TEXT) + + def redirect_output(self): + class StdoutRedirector: + def __init__(self, text_widget): + self.text_widget = text_widget + self.original_stdout = sys.stdout + + def write(self, message): + self.text_widget.insert(tk.END, message) + self.text_widget.see(tk.END) + self.original_stdout.write(message) + + def flush(self): + self.original_stdout.flush() + + sys.stdout = StdoutRedirector(self.log_text) + + def on_tree_click(self, event): + region = self.tree.identify("region", event.x, event.y) + if region == "cell": + col = self.tree.identify_column(event.x) + item = self.tree.identify_row(event.y) + if col == "#1": # 点击的是选中列 + current_val = self.tree.item(item, "values")[0] + new_val = "[√]" if current_val == "[ ]" else "[ ]" + self.tree.item(item, values=(new_val, self.tree.item(item, "values")[1])) + + def select_output_dir(self): + path = filedialog.askdirectory() + if path: + self.output_dir.set(path) + + def select_files(self): + files = filedialog.askopenfilenames(filetypes=[("图片文件", "*.png;*.jpg;*.jpeg;*.bmp;*.gif")]) + for f in files: + self.tree.insert("", tk.END, values=("[ ]", os.path.basename(f)), tags=(f,)) + + def remove_selected(self): + to_remove = [] + for item in self.tree.get_children(): + if self.tree.item(item, "values")[0] == "[√]": + to_remove.append(item) + for item in reversed(to_remove): + self.tree.delete(item) + + def clear_files(self): + for item in self.tree.get_children(): + self.tree.delete(item) + + def start_conversion(self, convert_all): + input_files = [ + self.tree.item(item, "tags")[0] + for item in self.tree.get_children() + if convert_all or self.tree.item(item, "values")[0] == "[√]" + ] + + if not input_files: + msg = "没有找到可转换的文件" if convert_all else "没有选中任何文件" + messagebox.showwarning("警告", msg) + return + + os.makedirs(self.output_dir.get(), exist_ok=True) + + # 解析转换参数 + width, height = map(int, self.resolution.get().split('x')) + compress = CompressMethod.RLE if self.compress_method.get() == "RLE" else CompressMethod.NONE + + # 执行转换 + self.convert_images(input_files, width, height, compress) + + def convert_images(self, input_files, width, height, compress): + success_count = 0 + total_files = len(input_files) + + for idx, file_path in enumerate(input_files): + try: + print(f"正在处理: {os.path.basename(file_path)}") + + with Image.open(file_path) as img: + # 调整图片大小 + img = img.resize((width, height), Image.Resampling.LANCZOS) + + # 处理颜色格式 + color_format_str = self.color_format.get() + if color_format_str == "自动识别": + # 检测透明通道 + has_alpha = img.mode in ('RGBA', 'LA') or (img.mode == 'P' and 'transparency' in img.info) + if has_alpha: + img = img.convert('RGBA') + cf = ColorFormat.RGB565A8 + else: + img = img.convert('RGB') + cf = ColorFormat.RGB565 + else: + if color_format_str == "RGB565A8": + img = img.convert('RGBA') + cf = ColorFormat.RGB565A8 + else: + img = img.convert('RGB') + cf = ColorFormat.RGB565 + + # 保存调整后的图片 + base_name = os.path.splitext(os.path.basename(file_path))[0] + output_image_path = os.path.join(self.output_dir.get(), f"{base_name}_{width}x{height}.png") + img.save(output_image_path, 'PNG') + + # 创建临时文件 + with tempfile.NamedTemporaryFile(suffix=".png", delete=False) as tmpfile: + temp_path = tmpfile.name + img.save(temp_path, 'PNG') + + # 转换为LVGL C数组 + lvgl_img = LVGLImage().from_png(temp_path, cf=cf) + output_c_path = os.path.join(self.output_dir.get(), f"{base_name}.c") + lvgl_img.to_c_array(output_c_path, compress=compress) + + success_count += 1 + os.unlink(temp_path) + print(f"成功转换: {base_name}.c\n") + + except Exception as e: + print(f"转换失败: {str(e)}\n") + + print(f"转换完成! 成功 {success_count}/{total_files} 个文件\n") + +if __name__ == "__main__": + root = tk.Tk() + app = ImageConverterApp(root) + root.mainloop() diff --git a/scripts/Image_Converter/requirements.txt b/scripts/Image_Converter/requirements.txt new file mode 100644 index 0000000..5dbc310 --- /dev/null +++ b/scripts/Image_Converter/requirements.txt @@ -0,0 +1,3 @@ +lz4==4.4.4 +Pillow==11.3.0 +pypng==0.20220715.0 diff --git a/scripts/acoustic_check/demod.py b/scripts/acoustic_check/demod.py new file mode 100644 index 0000000..89c8196 --- /dev/null +++ b/scripts/acoustic_check/demod.py @@ -0,0 +1,280 @@ +""" +实时AFSK解调器 - 基于Goertzel算法 +""" + +import numpy as np +from collections import deque + + +class TraceGoertzel: + """实时Goertzel算法实现""" + + def __init__(self, freq: float, n: int): + """ + 初始化Goertzel算法 + + Args: + freq: 归一化频率 (目标频率/采样频率) + n: 窗口大小 + """ + self.freq = freq + self.n = n + + # 预计算系数 - 与参考代码一致 + self.k = int(freq * n) + self.w = 2.0 * np.pi * freq + self.cw = np.cos(self.w) + self.sw = np.sin(self.w) + self.c = 2.0 * self.cw + + # 初始化状态变量 - 使用deque存储最近两个值 + self.zs = deque([0.0, 0.0], maxlen=2) + + def reset(self): + """重置算法状态""" + self.zs.clear() + self.zs.extend([0.0, 0.0]) + + def __call__(self, xs): + """ + 处理一组采样点 - 与参考代码一致的接口 + + Args: + xs: 采样点序列 + + Returns: + 计算出的振幅 + """ + self.reset() + for x in xs: + z1, z2 = self.zs[-1], self.zs[-2] # Z[-1], Z[-2] + z0 = x + self.c * z1 - z2 # S[n] = x[n] + C * S[n-1] - S[n-2] + self.zs.append(float(z0)) # 更新序列 + return self.amp + + @property + def amp(self) -> float: + """计算当前振幅 - 与参考代码一致""" + z1, z2 = self.zs[-1], self.zs[-2] + ip = self.cw * z1 - z2 + qp = self.sw * z1 + return np.sqrt(ip**2 + qp**2) / (self.n / 2.0) + + +class PairGoertzel: + """双频Goertzel解调器""" + + def __init__(self, f_sample: int, f_space: int, f_mark: int, + bit_rate: int, win_size: int): + """ + 初始化双频解调器 + + Args: + f_sample: 采样频率 + f_space: Space频率 (通常对应0) + f_mark: Mark频率 (通常对应1) + bit_rate: 比特率 + win_size: Goertzel窗口大小 + """ + assert f_sample % bit_rate == 0, "采样频率必须是比特率的整数倍" + + self.Fs = f_sample + self.F0 = f_space + self.F1 = f_mark + self.bit_rate = bit_rate + self.n_per_bit = int(f_sample // bit_rate) # 每个比特的采样点数 + + # 计算归一化频率 + f1 = f_mark / f_sample + f0 = f_space / f_sample + + # 初始化Goertzel算法 + self.g0 = TraceGoertzel(freq=f0, n=win_size) + self.g1 = TraceGoertzel(freq=f1, n=win_size) + + # 输入缓冲区 + self.in_buffer = deque(maxlen=win_size) + self.out_count = 0 + + print(f"PairGoertzel initialized: f0={f0:.6f}, f1={f1:.6f}, win_size={win_size}, n_per_bit={self.n_per_bit}") + + def __call__(self, s: float): + """ + 处理单个采样点 - 与参考代码一致的接口 + + Args: + s: 采样点值 + + Returns: + (amp0, amp1, p1_prob) - 空间频率振幅,标记频率振幅,标记概率 + """ + self.in_buffer.append(s) + self.out_count += 1 + + amp0, amp1, p1_prob = 0, 0, None + + # 每个比特周期输出一次结果 + if self.out_count >= self.n_per_bit: + amp0 = self.g0(self.in_buffer) # 计算space频率振幅 + amp1 = self.g1(self.in_buffer) # 计算mark频率振幅 + p1_prob = amp1 / (amp0 + amp1 + 1e-8) # 计算mark概率 + self.out_count = 0 + + return amp0, amp1, p1_prob + + +class RealTimeAFSKDecoder: + """实时AFSK解码器 - 基于起始帧触发""" + + def __init__(self, f_sample: int = 16000, mark_freq: int = 1800, + space_freq: int = 1500, bitrate: int = 100, + s_goertzel: int = 9, threshold: float = 0.5): + """ + 初始化实时AFSK解码器 + + Args: + f_sample: 采样频率 + mark_freq: Mark频率 + space_freq: Space频率 + bitrate: 比特率 + s_goertzel: Goertzel窗口大小系数 (win_size = f_sample // mark_freq * s_goertzel) + threshold: 判决门限 + """ + self.f_sample = f_sample + self.mark_freq = mark_freq + self.space_freq = space_freq + self.bitrate = bitrate + self.threshold = threshold + + # 计算窗口大小 - 与参考代码一致 + win_size = int(f_sample / mark_freq * s_goertzel) + + # 初始化解调器 + self.demodulator = PairGoertzel(f_sample, space_freq, mark_freq, + bitrate, win_size) + + # 帧定义 - 与参考代码一致 + self.start_bytes = b'\x01\x02' + self.end_bytes = b'\x03\x04' + self.start_bits = "".join(format(int(x), '08b') for x in self.start_bytes) + self.end_bits = "".join(format(int(x), '08b') for x in self.end_bytes) + + # 状态机 + self.state = "idle" # idle / entering + + # 存储解调结果 + self.buffer_prelude:deque = deque(maxlen=len(self.start_bits)) # 判断是否启动 + self.indicators = [] # 存储概率序列 + self.signal_bits = "" # 存储比特序列 + self.text_cache = "" + + # 解码结果 + self.decoded_messages = [] + self.total_bits_received = 0 + + print(f"Decoder initialized: win_size={win_size}") + print(f"Start frame: {self.start_bits} (from {self.start_bytes.hex()})") + print(f"End frame: {self.end_bits} (from {self.end_bytes.hex()})") + + def process_audio(self, samples: np.array) -> str: + """ + 处理音频数据并返回解码文本 + + Args: + audio_data: 音频字节数据 (16-bit PCM) + + Returns: + 新解码的文本 + """ + new_text = "" + # 逐个处理采样点 + for sample in samples: + amp0, amp1, p1_prob = self.demodulator(sample) + # 如果有概率输出,记录并判决 + if p1_prob is not None: + bit = '1' if p1_prob > self.threshold else '0' + match self.state: + case "idle": + self.buffer_prelude.append(bit) + pass + case "entering": + self.buffer_prelude.append(bit) + self.signal_bits += bit + self.total_bits_received += 1 + case _: + pass + self.indicators.append(p1_prob) + + # 检查状态机 + if self.state == "idle" and "".join(self.buffer_prelude) == self.start_bits: + self.state = "entering" + self.text_cache = "" + self.signal_bits = "" # 清空比特序列 + self.buffer_prelude.clear() + elif self.state == "entering" and ("".join(self.buffer_prelude) == self.end_bits or len(self.signal_bits) >= 256): + self.state = "idle" + self.buffer_prelude.clear() + + # 每收集一定数量的比特后尝试解码 + if len(self.signal_bits) >= 8: + text = self._decode_bits_to_text(self.signal_bits) + if len(text) > len(self.text_cache): + new_text = text[len(self.text_cache) - len(text):] + self.text_cache = text + return new_text + + def _decode_bits_to_text(self, bits: str) -> str: + """ + 将比特串解码为文本 + + Args: + bits: 比特串 + + Returns: + 解码出的文本 + """ + if len(bits) < 8: + return "" + + decoded_text = "" + byte_count = len(bits) // 8 + + for i in range(byte_count): + # 提取8位 + byte_bits = bits[i*8:(i+1)*8] + + # 位转字节 + byte_val = int(byte_bits, 2) + + # 尝试解码为ASCII字符 + if 32 <= byte_val <= 126: # 可打印ASCII字符 + decoded_text += chr(byte_val) + elif byte_val == 0: # NULL字符,忽略 + continue + else: + # 非可打印字符pass,以十六进制显示 + pass + # decoded_text += f"\\x{byte_val:02X}" + + return decoded_text + + def clear(self): + """清空解码状态""" + self.indicators = [] + self.signal_bits = "" + self.decoded_messages = [] + self.total_bits_received = 0 + print("解码器状态已清空") + + def get_stats(self) -> dict: + """获取解码统计信息""" + return { + 'prelude_bits': "".join(self.buffer_prelude), + "state": self.state, + 'total_chars': sum(len(msg) for msg in self.text_cache), + 'buffer_bits': len(self.signal_bits), + 'mark_freq': self.mark_freq, + 'space_freq': self.space_freq, + 'bitrate': self.bitrate, + 'threshold': self.threshold, + } diff --git a/scripts/acoustic_check/graphic.py b/scripts/acoustic_check/graphic.py new file mode 100644 index 0000000..e60cf06 --- /dev/null +++ b/scripts/acoustic_check/graphic.py @@ -0,0 +1,444 @@ +import sys +import numpy as np +import asyncio +import wave +from collections import deque +import qasync + +import matplotlib +matplotlib.use('qtagg') + +from matplotlib.backends.backend_qtagg import FigureCanvasQTAgg as FigureCanvas +from matplotlib.backends.backend_qtagg import NavigationToolbar2QT as NavigationToolbar # noqa: F401 +from matplotlib.figure import Figure + +from PyQt6.QtWidgets import (QApplication, QMainWindow, QVBoxLayout, QWidget, + QHBoxLayout, QLineEdit, QPushButton, QLabel, QTextEdit) +from PyQt6.QtCore import QTimer + +# 导入解码器 +from demod import RealTimeAFSKDecoder + + +class UDPServerProtocol(asyncio.DatagramProtocol): + """UDP服务器协议类""" + def __init__(self, data_queue): + self.client_address = None + self.data_queue: deque = data_queue + + def connection_made(self, transport): + self.transport = transport + + def datagram_received(self, data, addr): + # 如果还没有客户端地址,记录第一个连接的客户端 + if self.client_address is None: + self.client_address = addr + print(f"接受来自 {addr} 的连接") + + # 只处理来自已记录客户端的数据 + if addr == self.client_address: + # 将接收到的音频数据添加到队列 + self.data_queue.extend(data) + else: + print(f"忽略来自未知地址 {addr} 的数据") + + +class MatplotlibWidget(QWidget): + def __init__(self, parent=None): + super().__init__(parent) + + # 创建 Matplotlib 的 Figure 对象 + self.figure = Figure() + + # 创建 FigureCanvas 对象,它是 Figure 的 QWidget 容器 + self.canvas = FigureCanvas(self.figure) + + # 创建 Matplotlib 的导航工具栏 + # self.toolbar = NavigationToolbar(self.canvas, self) + self.toolbar = None + + # 创建布局 + layout = QVBoxLayout() + layout.addWidget(self.toolbar) + layout.addWidget(self.canvas) + self.setLayout(layout) + + # 初始化音频数据参数 + self.freq = 16000 # 采样频率 + self.time_window = 20 # 显示时间窗口 + self.wave_data = deque(maxlen=self.freq * self.time_window * 2) # 缓冲队列, 用于分发计算/绘图 + self.signals = deque(maxlen=self.freq * self.time_window) # 双端队列存储信号数据 + + # 创建包含两个子图的画布 + self.ax1 = self.figure.add_subplot(2, 1, 1) + self.ax2 = self.figure.add_subplot(2, 1, 2) + + # 时域子图 + self.ax1.set_title('Real-time Audio Waveform') + self.ax1.set_xlabel('Sample Index') + self.ax1.set_ylabel('Amplitude') + self.line_time, = self.ax1.plot([], []) + self.ax1.grid(True, alpha=0.3) + + # 频域子图 + self.ax2.set_title('Real-time Frequency Spectrum') + self.ax2.set_xlabel('Frequency (Hz)') + self.ax2.set_ylabel('Magnitude') + self.line_freq, = self.ax2.plot([], []) + self.ax2.grid(True, alpha=0.3) + + self.figure.tight_layout() + + # 定时器用于更新图表 + self.timer = QTimer(self) + self.timer.setInterval(100) # 100毫秒更新一次 + self.timer.timeout.connect(self.update_plot) + + # 初始化AFSK解码器 + self.decoder = RealTimeAFSKDecoder( + f_sample=self.freq, + mark_freq=1800, + space_freq=1500, + bitrate=100, + s_goertzel=9, + threshold=0.5 + ) + + # 解码结果回调 + self.decode_callback = None + + def start_plotting(self): + """开始绘图""" + self.timer.start() + + def stop_plotting(self): + """停止绘图""" + self.timer.stop() + + def update_plot(self): + """更新绘图数据""" + if len(self.wave_data) >= 2: + # 进行实时解码 + # 获取最新的音频数据进行解码 + even = len(self.wave_data) // 2 * 2 + print(f"length of wave_data: {len(self.wave_data)}") + drained = [self.wave_data.popleft() for _ in range(even)] + signal = np.frombuffer(bytearray(drained), dtype=' 0: + # 只显示最近的一段数据,避免图表过于密集 + signal = np.array(self.signals) + max_samples = min(len(signal), self.freq * self.time_window) + if len(signal) > max_samples: + signal = signal[-max_samples:] + + # 更新时域图 + x = np.arange(len(signal)) + self.line_time.set_data(x, signal) + + # 自动调整时域坐标轴范围 + if len(signal) > 0: + self.ax1.set_xlim(0, len(signal)) + y_min, y_max = np.min(signal), np.max(signal) + if y_min != y_max: + margin = (y_max - y_min) * 0.1 + self.ax1.set_ylim(y_min - margin, y_max + margin) + else: + self.ax1.set_ylim(-1, 1) + + # 计算频谱(短时离散傅立叶变换) + if len(signal) > 1: + # 计算FFT + fft_signal = np.abs(np.fft.fft(signal)) + frequencies = np.fft.fftfreq(len(signal), 1/self.freq) + + # 只取正频率部分 + positive_freq_idx = frequencies >= 0 + freq_positive = frequencies[positive_freq_idx] + fft_positive = fft_signal[positive_freq_idx] + + # 更新频域图 + self.line_freq.set_data(freq_positive, fft_positive) + + # 自动调整频域坐标轴范围 + if len(fft_positive) > 0: + # 限制频率显示范围到0-4000Hz,避免过于密集 + max_freq_show = min(4000, self.freq // 2) + freq_mask = freq_positive <= max_freq_show + if np.any(freq_mask): + self.ax2.set_xlim(0, max_freq_show) + fft_masked = fft_positive[freq_mask] + if len(fft_masked) > 0: + fft_max = np.max(fft_masked) + if fft_max > 0: + self.ax2.set_ylim(0, fft_max * 1.1) + else: + self.ax2.set_ylim(0, 1) + + self.canvas.draw() + + +class MainWindow(QMainWindow): + def __init__(self): + super().__init__() + self.setWindowTitle("Acoustic Check") + self.setGeometry(100, 100, 1000, 800) + + # 主窗口部件 + main_widget = QWidget() + self.setCentralWidget(main_widget) + + # 主布局 + main_layout = QVBoxLayout(main_widget) + + # 绘图区域 + self.matplotlib_widget = MatplotlibWidget() + main_layout.addWidget(self.matplotlib_widget) + + # 控制面板 + control_panel = QWidget() + control_layout = QHBoxLayout(control_panel) + + # 监听地址和端口输入 + control_layout.addWidget(QLabel("监听地址:")) + self.address_input = QLineEdit("0.0.0.0") + self.address_input.setFixedWidth(120) + control_layout.addWidget(self.address_input) + + control_layout.addWidget(QLabel("端口:")) + self.port_input = QLineEdit("8000") + self.port_input.setFixedWidth(80) + control_layout.addWidget(self.port_input) + + # 监听按钮 + self.listen_button = QPushButton("开始监听") + self.listen_button.clicked.connect(self.toggle_listening) + control_layout.addWidget(self.listen_button) + + # 状态标签 + self.status_label = QLabel("状态: 未连接") + control_layout.addWidget(self.status_label) + + # 数据统计标签 + self.data_label = QLabel("接收数据: 0 bytes") + control_layout.addWidget(self.data_label) + + # 保存按钮 + self.save_button = QPushButton("保存音频") + self.save_button.clicked.connect(self.save_audio) + self.save_button.setEnabled(False) + control_layout.addWidget(self.save_button) + + control_layout.addStretch() # 添加弹性空间 + + main_layout.addWidget(control_panel) + + # 解码显示区域 + decode_panel = QWidget() + decode_layout = QVBoxLayout(decode_panel) + + # 解码标题 + decode_title = QLabel("实时AFSK解码结果:") + decode_title.setStyleSheet("font-weight: bold; font-size: 14px;") + decode_layout.addWidget(decode_title) + + # 解码文本显示 + self.decode_text = QTextEdit() + self.decode_text.setMaximumHeight(150) + self.decode_text.setReadOnly(True) + self.decode_text.setStyleSheet("font-family: 'Courier New', monospace; font-size: 12px;") + decode_layout.addWidget(self.decode_text) + + # 解码控制按钮 + decode_control_layout = QHBoxLayout() + + # 清空按钮 + self.clear_decode_button = QPushButton("清空解码") + self.clear_decode_button.clicked.connect(self.clear_decode_text) + decode_control_layout.addWidget(self.clear_decode_button) + + # 解码统计标签 + self.decode_stats_label = QLabel("解码统计: 0 bits, 0 chars") + decode_control_layout.addWidget(self.decode_stats_label) + + decode_control_layout.addStretch() + decode_layout.addLayout(decode_control_layout) + + main_layout.addWidget(decode_panel) + + # 设置解码回调 + self.matplotlib_widget.decode_callback = self.on_decode_text + + # UDP相关属性 + self.udp_transport = None + self.is_listening = False + + # 数据统计定时器 + self.stats_timer = QTimer(self) + self.stats_timer.setInterval(1000) # 每秒更新一次统计 + self.stats_timer.timeout.connect(self.update_stats) + + def on_decode_text(self, new_text: str): + """解码文本回调""" + if new_text: + # 添加新解码的文本 + current_text = self.decode_text.toPlainText() + updated_text = current_text + new_text + + # 限制文本长度,保留最新的1000个字符 + if len(updated_text) > 1000: + updated_text = updated_text[-1000:] + + self.decode_text.setPlainText(updated_text) + + # 滚动到底部 + cursor = self.decode_text.textCursor() + cursor.movePosition(cursor.MoveOperation.End) + self.decode_text.setTextCursor(cursor) + + def clear_decode_text(self): + """清空解码文本""" + self.decode_text.clear() + if hasattr(self.matplotlib_widget, 'decoder'): + self.matplotlib_widget.decoder.clear() + self.decode_stats_label.setText("解码统计: 0 bits, 0 chars") + + def update_decode_stats(self): + """更新解码统计""" + if hasattr(self.matplotlib_widget, 'decoder'): + stats = self.matplotlib_widget.decoder.get_stats() + stats_text = ( + f"前置: {stats['prelude_bits']} , 已接收{stats['total_chars']} chars, " + f"缓冲: {stats['buffer_bits']} bits, 状态: {stats['state']}" + ) + self.decode_stats_label.setText(stats_text) + + def toggle_listening(self): + """切换监听状态""" + if not self.is_listening: + self.start_listening() + else: + self.stop_listening() + + async def start_listening_async(self): + """异步启动UDP监听""" + try: + address = self.address_input.text().strip() + port = int(self.port_input.text().strip()) + + loop = asyncio.get_running_loop() + self.udp_transport, protocol = await loop.create_datagram_endpoint( + lambda: UDPServerProtocol(self.matplotlib_widget.wave_data), + local_addr=(address, port) + ) + + self.status_label.setText(f"状态: 监听中 ({address}:{port})") + print(f"UDP服务器启动, 监听 {address}:{port}") + + except Exception as e: + self.status_label.setText(f"状态: 启动失败 - {str(e)}") + print(f"UDP服务器启动失败: {e}") + self.is_listening = False + self.listen_button.setText("开始监听") + self.address_input.setEnabled(True) + self.port_input.setEnabled(True) + + def start_listening(self): + """开始监听""" + try: + int(self.port_input.text().strip()) # 验证端口号格式 + except ValueError: + self.status_label.setText("状态: 端口号必须是数字") + return + + self.is_listening = True + self.listen_button.setText("停止监听") + self.address_input.setEnabled(False) + self.port_input.setEnabled(False) + self.save_button.setEnabled(True) + + # 清空数据队列 + self.matplotlib_widget.wave_data.clear() + + # 启动绘图和统计更新 + self.matplotlib_widget.start_plotting() + self.stats_timer.start() + + # 异步启动UDP服务器 + loop = asyncio.get_event_loop() + loop.create_task(self.start_listening_async()) + + def stop_listening(self): + """停止监听""" + self.is_listening = False + self.listen_button.setText("开始监听") + self.address_input.setEnabled(True) + self.port_input.setEnabled(True) + + # 停止UDP服务器 + if self.udp_transport: + self.udp_transport.close() + self.udp_transport = None + + # 停止绘图和统计更新 + self.matplotlib_widget.stop_plotting() + self.matplotlib_widget.wave_data.clear() + self.stats_timer.stop() + + self.status_label.setText("状态: 已停止") + + def update_stats(self): + """更新数据统计""" + data_size = len(self.matplotlib_widget.signals) + self.data_label.setText(f"接收数据: {data_size} 采样") + + # 更新解码统计 + self.update_decode_stats() + + def save_audio(self): + """保存音频数据""" + if len(self.matplotlib_widget.signals) > 0: + try: + signal_data = np.array(self.matplotlib_widget.signals) + + # 保存为WAV文件 + with wave.open("received_audio.wav", "wb") as wf: + wf.setnchannels(1) # 单声道 + wf.setsampwidth(2) # 采样宽度为2字节 + wf.setframerate(self.matplotlib_widget.freq) # 设置采样率 + wf.writeframes(signal_data.tobytes()) # 写入数据 + + self.status_label.setText("状态: 音频已保存为 received_audio.wav") + print("音频已保存为 received_audio.wav") + + except Exception as e: + self.status_label.setText(f"状态: 保存失败 - {str(e)}") + print(f"保存音频失败: {e}") + else: + self.status_label.setText("状态: 没有足够的数据可保存") + + +async def main(): + """异步主函数""" + app = QApplication(sys.argv) + + # 设置异步事件循环 + loop = qasync.QEventLoop(app) + asyncio.set_event_loop(loop) + + window = MainWindow() + window.show() + + try: + with loop: + await loop.run_forever() + except KeyboardInterrupt: + print("程序被用户中断") + finally: + # 确保清理资源 + if window.udp_transport: + window.udp_transport.close() \ No newline at end of file diff --git a/scripts/acoustic_check/main.py b/scripts/acoustic_check/main.py new file mode 100644 index 0000000..63ec849 --- /dev/null +++ b/scripts/acoustic_check/main.py @@ -0,0 +1,18 @@ +#!/usr/bin/env python3 +""" +音频实时监听与绘图系统主程序 +基于Qt GUI + Matplotlib + UDP接收 + AFSK解码字符串 +""" + +import sys +import asyncio +from graphic import main + +if __name__ == '__main__': + try: + asyncio.run(main()) + except KeyboardInterrupt: + print("程序被用户中断") + except Exception as e: + print(f"程序执行出错: {e}") + sys.exit(1) diff --git a/scripts/acoustic_check/readme.md b/scripts/acoustic_check/readme.md new file mode 100644 index 0000000..9eb9c7c --- /dev/null +++ b/scripts/acoustic_check/readme.md @@ -0,0 +1,23 @@ +# 声波测试 +该gui用于测试接受小智设备通过`udp`回传的`pcm`转时域/频域, 可以保存窗口长度的声音, 用于判断噪音频率分布和测试声波传输ascii的准确度, + +固件测试需要打开`USE_AUDIO_DEBUGGER`, 并设置好`AUDIO_DEBUG_UDP_SERVER`是本机地址. +声波`demod`可以通过`sonic_wifi_config.html`或者上传至`PinMe`的[小智声波配网](https://iqf7jnhi.pinit.eth.limo)来输出声波测试 + +# 声波解码测试记录 + +> `✓`代表在I2S DIN接收原始PCM信号时就能成功解码, `△`代表需要降噪或额外操作可稳定解码, `X`代表降噪后效果也不好(可能能解部分但非常不稳定)。 +> 个别ADC需要I2C配置阶段做更精细的降噪调整, 由于设备不通用暂只按照boards内提供的config测试 + +| 设备 | ADC | MIC | 效果 | 备注 | +| ---- | ---- | --- | --- | ---- | +| bread-compact | INMP441 | 集成MEMEMIC | ✓ | +| atk-dnesp32s3-box | ES8311 | | ✓ | +| magiclick-2p5 | ES8311 | | ✓ | +| lichuang-dev | ES7210 | | △ | 测试时需要关掉INPUT_REFERENCE +| kevin-box-2 | ES7210 | | △ | 测试时需要关掉INPUT_REFERENCE +| m5stack-core-s3 | ES7210 | | △ | 测试时需要关掉INPUT_REFERENCE +| xmini-c3 | ES8311 | | △ | 需降噪 +| atoms3r-echo-base | ES8311 | | △ | 需降噪 +| atk-dnesp32s3-box0 | ES8311 | | X | 能接收且解码, 但是丢包率很高 +| movecall-moji-esp32s3 | ES8311 | | X | 能接收且解码, 但是丢包率很高 \ No newline at end of file diff --git a/scripts/acoustic_check/requirements.txt b/scripts/acoustic_check/requirements.txt new file mode 100644 index 0000000..91bc5ec --- /dev/null +++ b/scripts/acoustic_check/requirements.txt @@ -0,0 +1,4 @@ +matplotlib==3.10.5 +numpy==2.3.2 +PyQt6==6.9.1 +qasync==0.27.1 diff --git a/scripts/audio_debug_server.py b/scripts/audio_debug_server.py new file mode 100644 index 0000000..872c490 --- /dev/null +++ b/scripts/audio_debug_server.py @@ -0,0 +1,54 @@ +import socket +import wave +import argparse + + +''' + Create a UDP socket and bind it to the server's IP:8000. + Listen for incoming messages and print them to the console. + Save the audio to a WAV file. +''' +def main(samplerate, channels): + # Create a UDP socket + server_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + server_socket.bind(('0.0.0.0', 8000)) + + # Create WAV file with parameters + filename = f"{samplerate}_{channels}.wav" + wav_file = wave.open(filename, "wb") + wav_file.setnchannels(channels) # channels parameter + wav_file.setsampwidth(2) # 2 bytes per sample (16-bit) + wav_file.setframerate(samplerate) # samplerate parameter + + print(f"Start saving audio from 0.0.0.0:8000 to {filename}...") + + try: + while True: + # Receive a message from the client + message, address = server_socket.recvfrom(8000) + + # Write PCM data to WAV file + wav_file.writeframes(message) + + # Print length of the message + print(f"Received {len(message)} bytes from {address}") + + except KeyboardInterrupt: + print("\nStopping recording...") + + finally: + # Close files and socket + wav_file.close() + server_socket.close() + print(f"WAV file '{filename}' saved successfully") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='UDP音频数据接收器,保存为WAV文件') + parser.add_argument('--samplerate', '-s', type=int, default=16000, + help='采样率 (默认: 16000)') + parser.add_argument('--channels', '-c', type=int, default=2, + help='声道数 (默认: 2)') + + args = parser.parse_args() + main(args.samplerate, args.channels) diff --git a/scripts/build_default_assets.py b/scripts/build_default_assets.py new file mode 100755 index 0000000..37e4e01 --- /dev/null +++ b/scripts/build_default_assets.py @@ -0,0 +1,882 @@ +#!/usr/bin/env python3 +""" +Build default assets based on configuration + +This script reads configuration from sdkconfig and builds the appropriate assets.bin +for the current board configuration. + +Usage: + ./build_default_assets.py --sdkconfig --builtin_text_font \ + --default_emoji_collection --output +""" + +import argparse +import io +import os +import shutil +import sys +import json +import struct +from datetime import datetime + + +# ============================================================================= +# Pack model functions (from pack_model.py) +# ============================================================================= + +def struct_pack_string(string, max_len=None): + """ + pack string to binary data. + if max_len is None, max_len = len(string) + 1 + else len(string) < max_len, the left will be padded by struct.pack('x') + """ + if max_len == None : + max_len = len(string) + else: + assert len(string) <= max_len + + left_num = max_len - len(string) + out_bytes = None + for char in string: + if out_bytes == None: + out_bytes = struct.pack('b', ord(char)) + else: + out_bytes += struct.pack('b', ord(char)) + for i in range(left_num): + out_bytes += struct.pack('x') + return out_bytes + + +def read_data(filename): + """Read binary data, like index and mndata""" + data = None + with open(filename, "rb") as f: + data = f.read() + return data + + +def pack_models(model_path, out_file="srmodels.bin"): + """ + Pack all models into one binary file by the following format: + { + model_num: int + model1_info: model_info_t + model2_info: model_info_t + ... + model1_index,model1_data,model1_MODEL_INFO + model1_index,model1_data,model1_MODEL_INFO + ... + }model_pack_t + + { + model_name: char[32] + file_number: int + file1_name: char[32] + file1_start: int + file1_len: int + file2_name: char[32] + file2_start: int // data_len = info_start - data_start + file2_len: int + ... + }model_info_t + """ + models = {} + file_num = 0 + model_num = 0 + for root, dirs, _ in os.walk(model_path): + for model_name in dirs: + models[model_name] = {} + model_dir = os.path.join(root, model_name) + model_num += 1 + for _, _, files in os.walk(model_dir): + for file_name in files: + file_num += 1 + file_path = os.path.join(model_dir, file_name) + models[model_name][file_name] = read_data(file_path) + + model_num = len(models) + header_len = 4 + model_num*(32+4) + file_num*(32+4+4) + out_bin = struct.pack('I', model_num) # model number + data_bin = None + for key in models: + model_bin = struct_pack_string(key, 32) # + model name + model_bin += struct.pack('I', len(models[key])) # + file number in this model + + for file_name in models[key]: + model_bin += struct_pack_string(file_name, 32) # + file name + if data_bin == None: + model_bin += struct.pack('I', header_len) + data_bin = models[key][file_name] + model_bin += struct.pack('I', len(models[key][file_name])) + else: + model_bin += struct.pack('I', header_len+len(data_bin)) + data_bin += models[key][file_name] + model_bin += struct.pack('I', len(models[key][file_name])) + + out_bin += model_bin + assert len(out_bin) == header_len + if data_bin != None: + out_bin += data_bin + + out_file = os.path.join(model_path, out_file) + with open(out_file, "wb") as f: + f.write(out_bin) + + +# ============================================================================= +# Build assets functions (from build.py) +# ============================================================================= + +def ensure_dir(directory): + """Ensure directory exists, create if not""" + os.makedirs(directory, exist_ok=True) + + +def copy_file(src, dst): + """Copy file""" + if os.path.exists(src): + shutil.copy2(src, dst) + print(f"Copied: {src} -> {dst}") + return True + else: + print(f"Warning: Source file does not exist: {src}") + return False + + +def copy_directory(src, dst): + """Copy directory""" + if os.path.exists(src): + shutil.copytree(src, dst, dirs_exist_ok=True) + print(f"Copied directory: {src} -> {dst}") + return True + else: + print(f"Warning: Source directory does not exist: {src}") + return False + + +def process_sr_models(wakenet_model_dirs, multinet_model_dirs, build_dir, assets_dir): + """Process SR models (wakenet and multinet) and generate srmodels.bin""" + if not wakenet_model_dirs and not multinet_model_dirs: + return None + + # Create SR models build directory + sr_models_build_dir = os.path.join(build_dir, "srmodels") + if os.path.exists(sr_models_build_dir): + shutil.rmtree(sr_models_build_dir) + os.makedirs(sr_models_build_dir) + + models_processed = 0 + + # Copy wakenet models if available + if wakenet_model_dirs: + for wakenet_model_dir in wakenet_model_dirs: + wakenet_name = os.path.basename(wakenet_model_dir) + wakenet_dst = os.path.join(sr_models_build_dir, wakenet_name) + if copy_directory(wakenet_model_dir, wakenet_dst): + models_processed += 1 + print(f"Added wakenet model: {wakenet_name}") + + # Copy multinet models if available + if multinet_model_dirs: + for multinet_model_dir in multinet_model_dirs: + multinet_name = os.path.basename(multinet_model_dir) + multinet_dst = os.path.join(sr_models_build_dir, multinet_name) + if copy_directory(multinet_model_dir, multinet_dst): + models_processed += 1 + print(f"Added multinet model: {multinet_name}") + + if models_processed == 0: + print("Warning: No SR models were successfully processed") + return None + + # Use pack_models function to generate srmodels.bin + srmodels_output = os.path.join(sr_models_build_dir, "srmodels.bin") + try: + pack_models(sr_models_build_dir, "srmodels.bin") + print(f"Generated: {srmodels_output}") + # Copy srmodels.bin to assets directory + copy_file(srmodels_output, os.path.join(assets_dir, "srmodels.bin")) + return "srmodels.bin" + except Exception as e: + print(f"Error: Failed to generate srmodels.bin: {e}") + return None + + +def process_text_font(text_font_file, assets_dir): + """Process text_font parameter""" + if not text_font_file: + return None + + # Copy input file to build/assets directory + font_filename = os.path.basename(text_font_file) + font_dst = os.path.join(assets_dir, font_filename) + if copy_file(text_font_file, font_dst): + return font_filename + return None + + +def process_emoji_collection(emoji_collection_dir, assets_dir): + """Process emoji_collection parameter""" + if not emoji_collection_dir: + return [] + + emoji_list = [] + + # Copy each image from input directory to build/assets directory + for root, dirs, files in os.walk(emoji_collection_dir): + for file in files: + if file.lower().endswith(('.png', '.gif')): + # Copy file + src_file = os.path.join(root, file) + dst_file = os.path.join(assets_dir, file) + if copy_file(src_file, dst_file): + # Get filename without extension + filename_without_ext = os.path.splitext(file)[0] + + # Add to emoji list + emoji_list.append({ + "name": filename_without_ext, + "file": file + }) + + return emoji_list + + +def process_extra_files(extra_files_dir, assets_dir): + """Process default_assets_extra_files parameter""" + if not extra_files_dir: + return [] + + if not os.path.exists(extra_files_dir): + print(f"Warning: Extra files directory not found: {extra_files_dir}") + return [] + + extra_files_list = [] + + # Copy each file from input directory to build/assets directory + for root, dirs, files in os.walk(extra_files_dir): + for file in files: + # Skip hidden files and directories + if file.startswith('.'): + continue + + # Copy file + src_file = os.path.join(root, file) + dst_file = os.path.join(assets_dir, file) + if copy_file(src_file, dst_file): + extra_files_list.append(file) + + if extra_files_list: + print(f"Processed {len(extra_files_list)} extra files from: {extra_files_dir}") + + return extra_files_list + + +def generate_index_json(assets_dir, srmodels, text_font, emoji_collection, extra_files=None, multinet_model_info=None): + """Generate index.json file""" + index_data = { + "version": 1 + } + + if srmodels: + index_data["srmodels"] = srmodels + + if text_font: + index_data["text_font"] = text_font + + if emoji_collection: + index_data["emoji_collection"] = emoji_collection + + if extra_files: + index_data["extra_files"] = extra_files + + if multinet_model_info: + index_data["multinet_model"] = multinet_model_info + + # Write index.json + index_path = os.path.join(assets_dir, "index.json") + with open(index_path, 'w', encoding='utf-8') as f: + json.dump(index_data, f, indent=4, ensure_ascii=False) + + print(f"Generated: {index_path}") + + +def generate_config_json(build_dir, assets_dir): + """Generate config.json file""" + config_data = { + "include_path": os.path.join(build_dir, "include"), + "assets_path": assets_dir, + "image_file": os.path.join(build_dir, "output", "assets.bin"), + "lvgl_ver": "9.3.0", + "assets_size": "0x400000", + "support_format": ".png, .gif, .jpg, .bin, .json", + "name_length": "32", + "split_height": "0", + "support_qoi": False, + "support_spng": False, + "support_sjpg": False, + "support_sqoi": False, + "support_raw": False, + "support_raw_dither": False, + "support_raw_bgr": False + } + + # Write config.json + config_path = os.path.join(build_dir, "config.json") + with open(config_path, 'w', encoding='utf-8') as f: + json.dump(config_data, f, indent=4, ensure_ascii=False) + + print(f"Generated: {config_path}") + return config_path + + +# ============================================================================= +# Simplified SPIFFS assets generation (from spiffs_assets_gen.py) +# ============================================================================= + +def compute_checksum(data): + checksum = sum(data) & 0xFFFF + return checksum + + +def sort_key(filename): + basename, extension = os.path.splitext(filename) + return extension, basename + + +def pack_assets_simple(target_path, include_path, out_file, assets_path, max_name_len=32): + """ + Simplified version of pack_assets that handles basic file packing + """ + merged_data = bytearray() + file_info_list = [] + skip_files = ['config.json'] + + # Ensure output directory exists + os.makedirs(os.path.dirname(out_file), exist_ok=True) + os.makedirs(include_path, exist_ok=True) + + file_list = sorted(os.listdir(target_path), key=sort_key) + for filename in file_list: + if filename in skip_files: + continue + + file_path = os.path.join(target_path, filename) + if not os.path.isfile(file_path): + continue + + file_name = os.path.basename(file_path) + file_size = os.path.getsize(file_path) + + file_info_list.append((file_name, len(merged_data), file_size, 0, 0)) + # Add 0x5A5A prefix to merged_data + merged_data.extend(b'\x5A' * 2) + + with open(file_path, 'rb') as bin_file: + bin_data = bin_file.read() + + merged_data.extend(bin_data) + + total_files = len(file_info_list) + + mmap_table = bytearray() + for file_name, offset, file_size, width, height in file_info_list: + if len(file_name) > max_name_len: + print(f'Warning: "{file_name}" exceeds {max_name_len} bytes and will be truncated.') + fixed_name = file_name.ljust(max_name_len, '\0')[:max_name_len] + mmap_table.extend(fixed_name.encode('utf-8')) + mmap_table.extend(file_size.to_bytes(4, byteorder='little')) + mmap_table.extend(offset.to_bytes(4, byteorder='little')) + mmap_table.extend(width.to_bytes(2, byteorder='little')) + mmap_table.extend(height.to_bytes(2, byteorder='little')) + + combined_data = mmap_table + merged_data + combined_checksum = compute_checksum(combined_data) + combined_data_length = len(combined_data).to_bytes(4, byteorder='little') + header_data = total_files.to_bytes(4, byteorder='little') + combined_checksum.to_bytes(4, byteorder='little') + final_data = header_data + combined_data_length + combined_data + + with open(out_file, 'wb') as output_bin: + output_bin.write(final_data) + + # Generate header file + current_year = datetime.now().year + asset_name = os.path.basename(assets_path) + header_file_path = os.path.join(include_path, f'mmap_generate_{asset_name}.h') + with open(header_file_path, 'w') as output_header: + output_header.write('/*\n') + output_header.write(' * SPDX-FileCopyrightText: 2022-{} Espressif Systems (Shanghai) CO LTD\n'.format(current_year)) + output_header.write(' *\n') + output_header.write(' * SPDX-License-Identifier: Apache-2.0\n') + output_header.write(' */\n\n') + output_header.write('/**\n') + output_header.write(' * @file\n') + output_header.write(" * @brief This file was generated by esp_mmap_assets, don't modify it\n") + output_header.write(' */\n\n') + output_header.write('#pragma once\n\n') + output_header.write("#include \"esp_mmap_assets.h\"\n\n") + output_header.write(f'#define MMAP_{asset_name.upper()}_FILES {total_files}\n') + output_header.write(f'#define MMAP_{asset_name.upper()}_CHECKSUM 0x{combined_checksum:04X}\n\n') + output_header.write(f'enum MMAP_{asset_name.upper()}_LISTS {{\n') + + for i, (file_name, _, _, _, _) in enumerate(file_info_list): + enum_name = file_name.replace('.', '_') + output_header.write(f' MMAP_{asset_name.upper()}_{enum_name.upper()} = {i}, /*!< {file_name} */\n') + + output_header.write('};\n') + + print(f'All files have been merged into {os.path.basename(out_file)}') + + +# ============================================================================= +# Configuration and main functions +# ============================================================================= + +def read_wakenet_from_sdkconfig(sdkconfig_path): + """ + Read wakenet models from sdkconfig (based on movemodel.py logic) + Returns a list of wakenet model names + """ + if not os.path.exists(sdkconfig_path): + print(f"Warning: sdkconfig file not found: {sdkconfig_path}") + return [] + + models = [] + with io.open(sdkconfig_path, "r") as f: + for label in f: + label = label.strip("\n") + if 'CONFIG_SR_WN' in label and '#' not in label[0]: + if '_NONE' in label: + continue + if '=' in label: + label = label.split("=")[0] + if '_MULTI' in label: + label = label[:-6] + model_name = label.split("_SR_WN_")[-1].lower() + models.append(model_name) + + return models + + +def read_multinet_from_sdkconfig(sdkconfig_path): + """ + Read multinet models from sdkconfig (based on movemodel.py logic) + Returns a list of multinet model names + """ + if not os.path.exists(sdkconfig_path): + print(f"Warning: sdkconfig file not found: {sdkconfig_path}") + return [] + + with io.open(sdkconfig_path, "r") as f: + models_string = '' + for label in f: + label = label.strip("\n") + if 'CONFIG_SR_MN' in label and label[0] != '#': + models_string += label + + models = [] + if "CONFIG_SR_MN_CN_MULTINET3_SINGLE_RECOGNITION" in models_string: + models.append('mn3_cn') + elif "CONFIG_SR_MN_CN_MULTINET4_5_SINGLE_RECOGNITION_QUANT8" in models_string: + models.append('mn4q8_cn') + elif "CONFIG_SR_MN_CN_MULTINET4_5_SINGLE_RECOGNITION" in models_string: + models.append('mn4_cn') + elif "CONFIG_SR_MN_CN_MULTINET5_RECOGNITION_QUANT8" in models_string: + models.append('mn5q8_cn') + elif "CONFIG_SR_MN_CN_MULTINET6_QUANT" in models_string: + models.append('mn6_cn') + elif "CONFIG_SR_MN_CN_MULTINET6_AC_QUANT" in models_string: + models.append('mn6_cn_ac') + elif "CONFIG_SR_MN_CN_MULTINET7_QUANT" in models_string: + models.append('mn7_cn') + elif "CONFIG_SR_MN_CN_MULTINET7_AC_QUANT" in models_string: + models.append('mn7_cn_ac') + + if "CONFIG_SR_MN_EN_MULTINET5_SINGLE_RECOGNITION_QUANT8" in models_string: + models.append('mn5q8_en') + elif "CONFIG_SR_MN_EN_MULTINET5_SINGLE_RECOGNITION" in models_string: + models.append('mn5_en') + elif "CONFIG_SR_MN_EN_MULTINET6_QUANT" in models_string: + models.append('mn6_en') + elif "CONFIG_SR_MN_EN_MULTINET7_QUANT" in models_string: + models.append('mn7_en') + + if "MULTINET6" in models_string or "MULTINET7" in models_string: + models.append('fst') + + return models + + +def read_wake_word_type_from_sdkconfig(sdkconfig_path): + """ + Read wake word type configuration from sdkconfig + Returns a dict with wake word type info + """ + if not os.path.exists(sdkconfig_path): + print(f"Warning: sdkconfig file not found: {sdkconfig_path}") + return { + 'use_esp_wake_word': False, + 'use_afe_wake_word': False, + 'use_custom_wake_word': False, + 'wake_word_disabled': True + } + + config_values = { + 'use_esp_wake_word': False, + 'use_afe_wake_word': False, + 'use_custom_wake_word': False, + 'wake_word_disabled': False + } + + with io.open(sdkconfig_path, "r") as f: + for line in f: + line = line.strip("\n") + if line.startswith('#'): + continue + + # Check for wake word type configuration + if 'CONFIG_USE_ESP_WAKE_WORD=y' in line: + config_values['use_esp_wake_word'] = True + elif 'CONFIG_USE_AFE_WAKE_WORD=y' in line: + config_values['use_afe_wake_word'] = True + elif 'CONFIG_USE_CUSTOM_WAKE_WORD=y' in line: + config_values['use_custom_wake_word'] = True + elif 'CONFIG_WAKE_WORD_DISABLED=y' in line: + config_values['wake_word_disabled'] = True + + return config_values + + +def read_custom_wake_word_from_sdkconfig(sdkconfig_path): + """ + Read custom wake word configuration from sdkconfig + Returns a dict with custom wake word info or None if not configured + """ + if not os.path.exists(sdkconfig_path): + print(f"Warning: sdkconfig file not found: {sdkconfig_path}") + return None + + config_values = {} + with io.open(sdkconfig_path, "r") as f: + for line in f: + line = line.strip("\n") + if line.startswith('#') or '=' not in line: + continue + + # Check for custom wake word configuration + if 'CONFIG_USE_CUSTOM_WAKE_WORD=y' in line: + config_values['use_custom_wake_word'] = True + elif 'CONFIG_CUSTOM_WAKE_WORD=' in line and not line.startswith('#'): + # Extract string value (remove quotes) + value = line.split('=', 1)[1].strip('"') + config_values['wake_word'] = value + elif 'CONFIG_CUSTOM_WAKE_WORD_DISPLAY=' in line and not line.startswith('#'): + # Extract string value (remove quotes) + value = line.split('=', 1)[1].strip('"') + config_values['display'] = value + elif 'CONFIG_CUSTOM_WAKE_WORD_THRESHOLD=' in line and not line.startswith('#'): + # Extract numeric value + value = line.split('=', 1)[1] + try: + config_values['threshold'] = int(value) + except ValueError: + try: + config_values['threshold'] = float(value) + except ValueError: + print(f"Warning: Invalid threshold value: {value}") + config_values['threshold'] = 20 # default (will be converted to 0.2) + + # Return config only if custom wake word is enabled and required fields are present + if (config_values.get('use_custom_wake_word', False) and + 'wake_word' in config_values and + 'display' in config_values and + 'threshold' in config_values): + return { + 'wake_word': config_values['wake_word'], + 'display': config_values['display'], + 'threshold': config_values['threshold'] / 100.0 # Convert to decimal (20 -> 0.2) + } + + return None + + +def get_language_from_multinet_models(multinet_models): + """ + Determine language from multinet model names + Returns 'cn', 'en', or None + """ + if not multinet_models: + return None + + # Check for Chinese models + cn_indicators = ['_cn', 'cn_'] + en_indicators = ['_en', 'en_'] + + has_cn = any(any(indicator in model for indicator in cn_indicators) for model in multinet_models) + has_en = any(any(indicator in model for indicator in en_indicators) for model in multinet_models) + + # If both or neither, default to cn + if has_cn and not has_en: + return 'cn' + elif has_en and not has_cn: + return 'en' + else: + return 'cn' # Default to Chinese + + +def get_wakenet_model_paths(model_names, esp_sr_model_path): + """ + Get the full paths to the wakenet model directories + Returns a list of valid model paths + """ + if not model_names: + return [] + + valid_paths = [] + for model_name in model_names: + wakenet_model_path = os.path.join(esp_sr_model_path, 'wakenet_model', model_name) + if os.path.exists(wakenet_model_path): + valid_paths.append(wakenet_model_path) + else: + print(f"Warning: Wakenet model directory not found: {wakenet_model_path}") + + return valid_paths + + +def get_multinet_model_paths(model_names, esp_sr_model_path): + """ + Get the full paths to the multinet model directories + Returns a list of valid model paths + """ + if not model_names: + return [] + + valid_paths = [] + for model_name in model_names: + multinet_model_path = os.path.join(esp_sr_model_path, 'multinet_model', model_name) + if os.path.exists(multinet_model_path): + valid_paths.append(multinet_model_path) + else: + print(f"Warning: Multinet model directory not found: {multinet_model_path}") + + return valid_paths + + +def get_text_font_path(builtin_text_font, xiaozhi_fonts_path): + """ + Get the text font path if needed + Returns the font file path or None if no font is needed + """ + if not builtin_text_font or 'basic' not in builtin_text_font: + return None + + # Convert from basic to common font name + # e.g., font_puhui_basic_16_4 -> font_puhui_common_16_4.bin + font_name = builtin_text_font.replace('basic', 'common') + '.bin' + font_path = os.path.join(xiaozhi_fonts_path, 'cbin', font_name) + + if os.path.exists(font_path): + return font_path + else: + print(f"Warning: Font file not found: {font_path}") + return None + + +def get_emoji_collection_path(default_emoji_collection, xiaozhi_fonts_path): + """ + Get the emoji collection path if needed + Returns the emoji directory path or None if no emoji collection is needed + """ + if not default_emoji_collection: + return None + + emoji_path = os.path.join(xiaozhi_fonts_path, 'png', default_emoji_collection) + if os.path.exists(emoji_path): + return emoji_path + else: + print(f"Warning: Emoji collection directory not found: {emoji_path}") + return None + + +def build_assets_integrated(wakenet_model_paths, multinet_model_paths, text_font_path, emoji_collection_path, extra_files_path, output_path, multinet_model_info=None): + """ + Build assets using integrated functions (no external dependencies) + """ + # Create temporary build directory + temp_build_dir = os.path.join(os.path.dirname(output_path), "temp_build") + assets_dir = os.path.join(temp_build_dir, "assets") + + try: + # Clean and create directories + if os.path.exists(temp_build_dir): + shutil.rmtree(temp_build_dir) + ensure_dir(temp_build_dir) + ensure_dir(assets_dir) + + print("Starting to build assets...") + + # Process each component + srmodels = process_sr_models(wakenet_model_paths, multinet_model_paths, temp_build_dir, assets_dir) if (wakenet_model_paths or multinet_model_paths) else None + text_font = process_text_font(text_font_path, assets_dir) if text_font_path else None + emoji_collection = process_emoji_collection(emoji_collection_path, assets_dir) if emoji_collection_path else None + extra_files = process_extra_files(extra_files_path, assets_dir) if extra_files_path else None + + # Generate index.json + generate_index_json(assets_dir, srmodels, text_font, emoji_collection, extra_files, multinet_model_info) + + # Generate config.json for packing + config_path = generate_config_json(temp_build_dir, assets_dir) + + # Load config and pack assets + with open(config_path, 'r') as f: + config_data = json.load(f) + + # Use simplified packing function + include_path = config_data['include_path'] + image_file = config_data['image_file'] + pack_assets_simple(assets_dir, include_path, image_file, "assets", int(config_data['name_length'])) + + # Copy final assets.bin to output location + if os.path.exists(image_file): + shutil.copy2(image_file, output_path) + print(f"Successfully generated assets.bin: {output_path}") + + # Show size information + total_size = os.path.getsize(output_path) + print(f"Assets file size: {total_size / 1024:.2f}K ({total_size} bytes)") + + return True + else: + print(f"Error: Generated assets.bin not found: {image_file}") + return False + + except Exception as e: + print(f"Error: Failed to build assets: {e}") + return False + finally: + # Clean up temporary directory + if os.path.exists(temp_build_dir): + shutil.rmtree(temp_build_dir) + + +def main(): + parser = argparse.ArgumentParser(description='Build default assets based on configuration') + parser.add_argument('--sdkconfig', required=True, help='Path to sdkconfig file') + parser.add_argument('--builtin_text_font', help='Builtin text font name (e.g., font_puhui_basic_16_4)') + parser.add_argument('--emoji_collection', help='Default emoji collection name (e.g., emojis_32)') + parser.add_argument('--output', required=True, help='Output path for assets.bin') + parser.add_argument('--esp_sr_model_path', help='Path to ESP-SR model directory') + parser.add_argument('--xiaozhi_fonts_path', help='Path to xiaozhi-fonts component directory') + parser.add_argument('--extra_files', help='Path to extra files directory to be included in assets') + + args = parser.parse_args() + + # Set default paths if not provided + if not args.esp_sr_model_path or not args.xiaozhi_fonts_path: + # Calculate project root from script location + script_dir = os.path.dirname(os.path.abspath(__file__)) + project_root = os.path.dirname(script_dir) + + if not args.esp_sr_model_path: + args.esp_sr_model_path = os.path.join(project_root, "managed_components", "espressif__esp-sr", "model") + + if not args.xiaozhi_fonts_path: + args.xiaozhi_fonts_path = os.path.join(project_root, "components", "xiaozhi-fonts") + + print("Building default assets...") + print(f" sdkconfig: {args.sdkconfig}") + print(f" builtin_text_font: {args.builtin_text_font}") + print(f" emoji_collection: {args.emoji_collection}") + print(f" output: {args.output}") + + # Read wake word type configuration from sdkconfig + wake_word_config = read_wake_word_type_from_sdkconfig(args.sdkconfig) + + # Read SR models from sdkconfig + wakenet_model_names = read_wakenet_from_sdkconfig(args.sdkconfig) + multinet_model_names = read_multinet_from_sdkconfig(args.sdkconfig) + + # Apply wake word logic to decide which models to package + wakenet_model_paths = [] + multinet_model_paths = [] + + # 1. Only package wakenet models if USE_ESP_WAKE_WORD=y or USE_AFE_WAKE_WORD=y + if wake_word_config['use_esp_wake_word'] or wake_word_config['use_afe_wake_word']: + wakenet_model_paths = get_wakenet_model_paths(wakenet_model_names, args.esp_sr_model_path) + elif wakenet_model_names: + print(f" Note: Found wakenet models {wakenet_model_names} but wake word type is not ESP/AFE, skipping") + + # 2. Error check: if USE_CUSTOM_WAKE_WORD=y but no multinet models selected, report error + if wake_word_config['use_custom_wake_word'] and not multinet_model_names: + print("Error: USE_CUSTOM_WAKE_WORD is enabled but no multinet models are selected in sdkconfig") + print("Please select appropriate CONFIG_SR_MN_* options in menuconfig, or disable USE_CUSTOM_WAKE_WORD") + sys.exit(1) + + # 3. Only package multinet models if USE_CUSTOM_WAKE_WORD=y + if wake_word_config['use_custom_wake_word']: + multinet_model_paths = get_multinet_model_paths(multinet_model_names, args.esp_sr_model_path) + elif multinet_model_names: + print(f" Note: Found multinet models {multinet_model_names} but USE_CUSTOM_WAKE_WORD is disabled, skipping") + + # Print model information (only for models that will actually be packaged) + if wakenet_model_paths: + print(f" wakenet models: {', '.join(wakenet_model_names)} (will be packaged)") + if multinet_model_paths: + print(f" multinet models: {', '.join(multinet_model_names)} (will be packaged)") + + # Get text font path if needed + text_font_path = get_text_font_path(args.builtin_text_font, args.xiaozhi_fonts_path) + + # Get emoji collection path if needed + emoji_collection_path = get_emoji_collection_path(args.emoji_collection, args.xiaozhi_fonts_path) + + # Get extra files path if provided + extra_files_path = args.extra_files + + # Read custom wake word configuration + custom_wake_word_config = read_custom_wake_word_from_sdkconfig(args.sdkconfig) + multinet_model_info = None + + if custom_wake_word_config and multinet_model_paths: + # Determine language from multinet models + language = get_language_from_multinet_models(multinet_model_names) + + # Build multinet_model info structure + multinet_model_info = { + "language": language, + "duration": 3000, # Default duration in ms + "threshold": custom_wake_word_config['threshold'], + "commands": [ + { + "command": custom_wake_word_config['wake_word'], + "text": custom_wake_word_config['display'], + "action": "wake" + } + ] + } + print(f" custom wake word: {custom_wake_word_config['wake_word']} ({custom_wake_word_config['display']})") + print(f" wake word language: {language}") + print(f" wake word threshold: {custom_wake_word_config['threshold']}") + + # Check if we have anything to build + if not wakenet_model_paths and not multinet_model_paths and not text_font_path and not emoji_collection_path and not extra_files_path and not multinet_model_info: + print("Warning: No assets to build (no SR models, text font, emoji collection, extra files, or custom wake word)") + # Create an empty assets.bin file + os.makedirs(os.path.dirname(args.output), exist_ok=True) + with open(args.output, 'wb') as f: + pass # Create empty file + print(f"Created empty assets.bin: {args.output}") + return + + # Build the assets + success = build_assets_integrated(wakenet_model_paths, multinet_model_paths, text_font_path, emoji_collection_path, + extra_files_path, args.output, multinet_model_info) + + if not success: + sys.exit(1) + + print("Build completed successfully!") + + +if __name__ == "__main__": + main() diff --git a/scripts/download_github_runs.py b/scripts/download_github_runs.py new file mode 100644 index 0000000..cd81217 --- /dev/null +++ b/scripts/download_github_runs.py @@ -0,0 +1,264 @@ +#!/usr/bin/env python3 +""" +Download GitHub Actions artifacts and rename them with version numbers. + +Usage: + python download_github_runs.py 2.0.4 https://github.com/78/xiaozhi-esp32/actions/runs/18866246016 +""" + +import argparse +import os +import re +import sys +import zipfile +from pathlib import Path +from urllib.parse import urlparse + +import requests +from dotenv import load_dotenv + + +def parse_github_run_url(url: str) -> tuple[str, str, str]: + """ + Parse GitHub Actions run URL to extract owner, repo, and run_id. + + Args: + url: GitHub Actions run URL + + Returns: + Tuple of (owner, repo, run_id) + """ + # Example: https://github.com/78/xiaozhi-esp32/actions/runs/18866246016 + pattern = r'github\.com/([^/]+)/([^/]+)/actions/runs/(\d+)' + match = re.search(pattern, url) + + if not match: + raise ValueError(f"Invalid GitHub Actions URL: {url}") + + owner, repo, run_id = match.groups() + return owner, repo, run_id + + +def get_artifacts(owner: str, repo: str, run_id: str, token: str) -> list[dict]: + """ + Get all artifacts for a specific workflow run (with pagination support). + + Args: + owner: Repository owner + repo: Repository name + run_id: Workflow run ID + token: GitHub personal access token + + Returns: + List of artifact dictionaries + """ + headers = { + "Authorization": f"Bearer {token}", + "Accept": "application/vnd.github+json", + "X-GitHub-Api-Version": "2022-11-28" + } + + all_artifacts = [] + page = 1 + per_page = 100 # Maximum allowed by GitHub API + + while True: + url = f"https://api.github.com/repos/{owner}/{repo}/actions/runs/{run_id}/artifacts" + params = { + "page": page, + "per_page": per_page + } + + response = requests.get(url, headers=headers, params=params) + response.raise_for_status() + + data = response.json() + artifacts = data.get("artifacts", []) + + if not artifacts: + break + + all_artifacts.extend(artifacts) + + # Check if there are more pages + total_count = data.get("total_count", 0) + if len(all_artifacts) >= total_count: + break + + page += 1 + + return all_artifacts + + +def download_artifact(artifact_url: str, token: str, output_path: Path) -> None: + """ + Download an artifact from GitHub. + + Args: + artifact_url: Artifact download URL + token: GitHub personal access token + output_path: Path to save the downloaded artifact + """ + headers = { + "Authorization": f"Bearer {token}", + "Accept": "application/vnd.github+json", + "X-GitHub-Api-Version": "2022-11-28" + } + + response = requests.get(artifact_url, headers=headers, stream=True) + response.raise_for_status() + + # Create parent directory if it doesn't exist + output_path.parent.mkdir(parents=True, exist_ok=True) + + # Download the file + with open(output_path, 'wb') as f: + for chunk in response.iter_content(chunk_size=8192): + if chunk: + f.write(chunk) + + +def rename_artifact(original_name: str, version: str) -> str: + """ + Rename artifact according to the specified rules. + + Rules: + - Remove "xiaozhi_" prefix + - Remove hash suffix (underscore followed by hex string) + - Add version prefix (e.g., "v2.0.4_") + - Change extension to .zip + + Example: + xiaozhi_atk-dnesp32s3-box0_43ef2f4e7f0957dc62ec7d628ac2819d226127b8.bin + -> v2.0.4_atk-dnesp32s3-box0.zip + + Args: + original_name: Original artifact name + version: Version string (e.g., "2.0.4") + + Returns: + New filename + """ + # Remove "xiaozhi_" prefix + name = original_name + if name.startswith("xiaozhi_"): + name = name[len("xiaozhi_"):] + + # Remove extension + name_without_ext = os.path.splitext(name)[0] + + # Remove hash suffix (pattern: underscore followed by 40+ hex characters) + # This matches Git commit hashes and similar identifiers + name_without_hash = re.sub(r'_[a-f0-9]{40,}$', '', name_without_ext) + + # Add version prefix and .zip extension + new_name = f"v{version}_{name_without_hash}.zip" + + return new_name + + +def main(): + """Main function to download and rename GitHub Actions artifacts.""" + parser = argparse.ArgumentParser( + description="Download GitHub Actions artifacts and rename them with version numbers." + ) + parser.add_argument( + "version", + help="Version number (e.g., 2.0.4)" + ) + parser.add_argument( + "url", + help="GitHub Actions run URL (e.g., https://github.com/owner/repo/actions/runs/12345)" + ) + parser.add_argument( + "--output-dir", + default="../releases", + help="Output directory for downloaded artifacts (default: ../releases)" + ) + + args = parser.parse_args() + + # Load GitHub token from .env file + load_dotenv() + github_token = os.getenv("GITHUB_TOKEN") + + if not github_token: + print("Error: GITHUB_TOKEN not found in environment variables.", file=sys.stderr) + print("Please create a .env file with GITHUB_TOKEN=your_token_here", file=sys.stderr) + sys.exit(1) + + try: + # Parse the GitHub URL + owner, repo, run_id = parse_github_run_url(args.url) + print(f"Repository: {owner}/{repo}") + print(f"Run ID: {run_id}") + print(f"Version: {args.version}") + print() + + # Get artifacts + print("Fetching artifacts...") + artifacts = get_artifacts(owner, repo, run_id, github_token) + + if not artifacts: + print("No artifacts found for this run.") + return + + print(f"Found {len(artifacts)} artifact(s):") + for artifact in artifacts: + print(f" - {artifact['name']}") + print() + + # Create output directory + output_dir = Path(args.output_dir) + output_dir.mkdir(parents=True, exist_ok=True) + + # Download and rename each artifact + downloaded_count = 0 + skipped_count = 0 + + for artifact in artifacts: + original_name = artifact['name'] + new_name = rename_artifact(original_name, args.version) + final_path = output_dir / new_name + + # Check if file already exists + if final_path.exists(): + print(f"Skipping (already exists): {original_name}") + print(f" -> {new_name}") + print(f" File: {final_path}") + print() + skipped_count += 1 + continue + + print(f"Downloading: {original_name}") + print(f" -> {new_name}") + + # Download to temporary path first + temp_path = output_dir / f"{original_name}.zip" + download_artifact( + artifact['archive_download_url'], + github_token, + temp_path + ) + + # Rename to final name + temp_path.rename(final_path) + + print(f" Saved to: {final_path}") + print() + downloaded_count += 1 + + print(f"Summary:") + print(f" Downloaded: {downloaded_count} artifact(s)") + print(f" Skipped: {skipped_count} artifact(s)") + print(f" Total: {len(artifacts)} artifact(s)") + print(f" Output directory: {output_dir.absolute()}") + + except Exception as e: + print(f"Error: {e}", file=sys.stderr) + sys.exit(1) + + +if __name__ == "__main__": + main() + diff --git a/scripts/gen_lang.py b/scripts/gen_lang.py new file mode 100644 index 0000000..81c0326 --- /dev/null +++ b/scripts/gen_lang.py @@ -0,0 +1,187 @@ +#!/usr/bin/env python3 +import argparse +import json +import os + +HEADER_TEMPLATE = """// Auto-generated language config +// Language: {lang_code} with en-US fallback +#pragma once + +#include + +#ifndef {lang_code_for_font} + #define {lang_code_for_font} // 預設語言 +#endif + +namespace Lang {{ + // 语言元数据 + constexpr const char* CODE = "{lang_code}"; + + // 字符串资源 (en-US as fallback for missing keys) + namespace Strings {{ +{strings} + }} + + // 音效资源 (en-US as fallback for missing audio files) + namespace Sounds {{ +{sounds} + }} +}} +""" + +def load_base_language(assets_dir): + """加载 en-US 基准语言数据""" + base_lang_path = os.path.join(assets_dir, 'locales', 'en-US', 'language.json') + if os.path.exists(base_lang_path): + try: + with open(base_lang_path, 'r', encoding='utf-8') as f: + base_data = json.load(f) + print(f"Loaded base language en-US with {len(base_data.get('strings', {}))} strings") + return base_data + except json.JSONDecodeError as e: + print(f"Warning: Failed to parse en-US language file: {e}") + else: + print("Warning: en-US base language file not found, fallback mechanism disabled") + return {'strings': {}} + +def get_sound_files(directory): + """获取目录中的音效文件列表""" + if not os.path.exists(directory): + return [] + return [f for f in os.listdir(directory) if f.endswith('.ogg')] + +def generate_header(lang_code, output_path): + # 从输出路径推导项目结构 + # output_path 通常是 main/assets/lang_config.h + main_dir = os.path.dirname(output_path) # main/assets + if os.path.basename(main_dir) == 'assets': + main_dir = os.path.dirname(main_dir) # main + project_dir = os.path.dirname(main_dir) # 项目根目录 + assets_dir = os.path.join(main_dir, 'assets') + + # 构建语言JSON文件路径 + input_path = os.path.join(assets_dir, 'locales', lang_code, 'language.json') + + print(f"Processing language: {lang_code}") + print(f"Input file path: {input_path}") + print(f"Output file path: {output_path}") + + if not os.path.exists(input_path): + raise FileNotFoundError(f"Language file not found: {input_path}") + + with open(input_path, 'r', encoding='utf-8') as f: + data = json.load(f) + + # 验证数据结构 + if 'language' not in data or 'strings' not in data: + raise ValueError("Invalid JSON structure") + + # 加载 en-US 基准语言数据 + base_data = load_base_language(assets_dir) + + # 合并字符串:以 en-US 为基准,用户语言覆盖 + base_strings = base_data.get('strings', {}) + user_strings = data['strings'] + merged_strings = base_strings.copy() + merged_strings.update(user_strings) + + # 统计信息 + base_count = len(base_strings) + user_count = len(user_strings) + total_count = len(merged_strings) + fallback_count = total_count - user_count + + print(f"Language {lang_code} string statistics:") + print(f" - Base language (en-US): {base_count} strings") + print(f" - User language: {user_count} strings") + print(f" - Total: {total_count} strings") + if fallback_count > 0: + print(f" - Fallback to en-US: {fallback_count} strings") + + # 生成字符串常量 + strings = [] + sounds = [] + for key, value in merged_strings.items(): + value = value.replace('"', '\\"') + strings.append(f' constexpr const char* {key.upper()} = "{value}";') + + # 收集音效文件:以 en-US 为基准,用户语言覆盖 + current_lang_dir = os.path.join(assets_dir, 'locales', lang_code) + base_lang_dir = os.path.join(assets_dir, 'locales', 'en-US') + common_dir = os.path.join(assets_dir, 'common') + + # 获取所有可能的音效文件 + base_sounds = get_sound_files(base_lang_dir) + current_sounds = get_sound_files(current_lang_dir) + common_sounds = get_sound_files(common_dir) + + # 合并音效文件列表:用户语言覆盖基准语言 + all_sound_files = set(base_sounds) + all_sound_files.update(current_sounds) + + # 音效统计信息 + base_sound_count = len(base_sounds) + user_sound_count = len(current_sounds) + common_sound_count = len(common_sounds) + sound_fallback_count = len(set(base_sounds) - set(current_sounds)) + + print(f"Language {lang_code} sound statistics:") + print(f" - Base language (en-US): {base_sound_count} sounds") + print(f" - User language: {user_sound_count} sounds") + print(f" - Common sounds: {common_sound_count} sounds") + if sound_fallback_count > 0: + print(f" - Sound fallback to en-US: {sound_fallback_count} sounds") + + # 生成语言特定音效常量 + for file in sorted(all_sound_files): + base_name = os.path.splitext(file)[0] + # 优先使用当前语言的音效,如果不存在则回退到 en-US + if file in current_sounds: + sound_lang = lang_code.replace('-', '_').lower() + else: + sound_lang = 'en_us' + + sounds.append(f''' + extern const char ogg_{base_name}_start[] asm("_binary_{base_name}_ogg_start"); + extern const char ogg_{base_name}_end[] asm("_binary_{base_name}_ogg_end"); + static const std::string_view OGG_{base_name.upper()} {{ + static_cast(ogg_{base_name}_start), + static_cast(ogg_{base_name}_end - ogg_{base_name}_start) + }};''') + + # 生成公共音效常量 + for file in sorted(common_sounds): + base_name = os.path.splitext(file)[0] + sounds.append(f''' + extern const char ogg_{base_name}_start[] asm("_binary_{base_name}_ogg_start"); + extern const char ogg_{base_name}_end[] asm("_binary_{base_name}_ogg_end"); + static const std::string_view OGG_{base_name.upper()} {{ + static_cast(ogg_{base_name}_start), + static_cast(ogg_{base_name}_end - ogg_{base_name}_start) + }};''') + + # 填充模板 + content = HEADER_TEMPLATE.format( + lang_code=lang_code, + lang_code_for_font=lang_code.replace('-', '_').lower(), + strings="\n".join(sorted(strings)), + sounds="\n".join(sorted(sounds)) + ) + + # 写入文件 + os.makedirs(os.path.dirname(output_path), exist_ok=True) + with open(output_path, 'w', encoding='utf-8') as f: + f.write(content) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Generate language configuration header file with en-US fallback") + parser.add_argument("--language", required=True, help="Language code (e.g: zh-CN, en-US, ja-JP)") + parser.add_argument("--output", required=True, help="Output header file path") + args = parser.parse_args() + + try: + generate_header(args.language, args.output) + print(f"Successfully generated language config file: {args.output}") + except Exception as e: + print(f"Error: {e}") + exit(1) \ No newline at end of file diff --git a/scripts/mp3_to_ogg.sh b/scripts/mp3_to_ogg.sh new file mode 100644 index 0000000..2cb870a --- /dev/null +++ b/scripts/mp3_to_ogg.sh @@ -0,0 +1,3 @@ +#!/bin/sh +# mp3_to_ogg.sh +ffmpeg -i $1 -c:a libopus -b:a 16k -ac 1 -ar 16000 -frame_duration 60 $2 diff --git a/scripts/ogg_converter/README.md b/scripts/ogg_converter/README.md new file mode 100644 index 0000000..eecbe42 --- /dev/null +++ b/scripts/ogg_converter/README.md @@ -0,0 +1,36 @@ +# ogg_covertor 小智AI OGG 音效批量转换器 + +本脚本为OGG批量转换工具,支持将输入的音频文件转换为小智可使用的OGG格式 + +基于Python第三方库 `ffmpeg-python` 实现,**需要** `ffmpeg` 环境 + +可前往[此处](https://ffmpeg.org/download.html)下载对应你自己系统的ffmpeg发行版,并添加到环境变量或者放在脚本所在目录 + +支持OGG和音频之间的互转,响度调节等功能 + +# 创建并激活虚拟环境 + +```bash +# 创建虚拟环境 +python -m venv venv +# 激活虚拟环境 +source venv/bin/activate # Mac/Linux +venv\Scripts\activate # Windows +``` +# 下载FFmpeg +前往[此处](https://ffmpeg.org/download.html)下载ffmpeg + +根据你当前的系统下载对应的版本,并将`ffmpeg`的可执行文件放置在脚本所在目录或者添加可执行文件所在目录到环境变量 + +# 安装依赖 +请在虚拟环境中执行 + +```bash +pip install ffmpeg-python +``` + +# 运行脚本 +```bash +python ogg_covertor.py +``` + diff --git a/scripts/ogg_converter/xiaozhi_ogg_converter.py b/scripts/ogg_converter/xiaozhi_ogg_converter.py new file mode 100644 index 0000000..5c3ddb2 --- /dev/null +++ b/scripts/ogg_converter/xiaozhi_ogg_converter.py @@ -0,0 +1,230 @@ +import tkinter as tk +from tkinter import ttk, filedialog, messagebox +import os +import threading +import sys +import ffmpeg + +class AudioConverterApp: + def __init__(self, master): + self.master = master + master.title("小智AI OGG音频批量转换工具") + master.geometry("680x600") # 调整窗口高度 + + # 初始化变量 + self.mode = tk.StringVar(value="audio_to_ogg") + self.output_dir = tk.StringVar() + self.output_dir.set(os.path.abspath("output")) + self.enable_loudnorm = tk.BooleanVar(value=True) + self.target_lufs = tk.DoubleVar(value=-16.0) + + # 创建UI组件 + self.create_widgets() + self.redirect_output() + + def create_widgets(self): + # 模式选择 + mode_frame = ttk.LabelFrame(self.master, text="转换模式") + mode_frame.grid(row=0, column=0, padx=10, pady=5, sticky="ew") + + ttk.Radiobutton(mode_frame, text="音频转到OGG", variable=self.mode, + value="audio_to_ogg", command=self.toggle_settings, + width=12).grid(row=0, column=0, padx=5) + ttk.Radiobutton(mode_frame, text="OGG转回音频", variable=self.mode, + value="ogg_to_audio", command=self.toggle_settings, + width=12).grid(row=0, column=1, padx=5) + + # 响度设置 + self.loudnorm_frame = ttk.Frame(self.master) + self.loudnorm_frame.grid(row=1, column=0, padx=10, pady=5, sticky="ew") + + ttk.Checkbutton(self.loudnorm_frame, text="启用响度调整", + variable=self.enable_loudnorm, width=15 + ).grid(row=0, column=0, padx=2) + ttk.Entry(self.loudnorm_frame, textvariable=self.target_lufs, + width=6).grid(row=0, column=1, padx=2) + ttk.Label(self.loudnorm_frame, text="LUFS").grid(row=0, column=2, padx=2) + + # 文件选择 + file_frame = ttk.LabelFrame(self.master, text="输入文件") + file_frame.grid(row=2, column=0, padx=10, pady=5, sticky="nsew") + + # 文件操作按钮 + ttk.Button(file_frame, text="选择文件", command=self.select_files, + width=12).grid(row=0, column=0, padx=5, pady=2) + ttk.Button(file_frame, text="移除选中", command=self.remove_selected, + width=12).grid(row=0, column=1, padx=5, pady=2) + ttk.Button(file_frame, text="清空列表", command=self.clear_files, + width=12).grid(row=0, column=2, padx=5, pady=2) + + # 文件列表(使用Treeview) + self.tree = ttk.Treeview(file_frame, columns=("selected", "filename"), + show="headings", height=8) + self.tree.heading("selected", text="选中", anchor=tk.W) + self.tree.heading("filename", text="文件名", anchor=tk.W) + self.tree.column("selected", width=60, anchor=tk.W) + self.tree.column("filename", width=600, anchor=tk.W) + self.tree.grid(row=1, column=0, columnspan=3, sticky="nsew", padx=5, pady=2) + self.tree.bind("", self.on_tree_click) + + # 输出目录 + output_frame = ttk.LabelFrame(self.master, text="输出目录") + output_frame.grid(row=3, column=0, padx=10, pady=5, sticky="ew") + + ttk.Entry(output_frame, textvariable=self.output_dir, width=60 + ).grid(row=0, column=0, padx=5, sticky="ew") + ttk.Button(output_frame, text="浏览", command=self.select_output_dir, + width=8).grid(row=0, column=1, padx=5) + + # 转换按钮区域 + button_frame = ttk.Frame(self.master) + button_frame.grid(row=4, column=0, padx=10, pady=10, sticky="ew") + + ttk.Button(button_frame, text="转换全部文件", command=lambda: self.start_conversion(True), + width=15).pack(side=tk.LEFT, padx=5) + ttk.Button(button_frame, text="转换选中文件", command=lambda: self.start_conversion(False), + width=15).pack(side=tk.LEFT, padx=5) + + # 日志区域 + log_frame = ttk.LabelFrame(self.master, text="日志") + log_frame.grid(row=5, column=0, padx=10, pady=5, sticky="nsew") + + self.log_text = tk.Text(log_frame, height=14, width=80) + self.log_text.pack(fill=tk.BOTH, expand=True) + + # 配置布局权重 + self.master.columnconfigure(0, weight=1) + self.master.rowconfigure(2, weight=1) + self.master.rowconfigure(5, weight=3) + file_frame.columnconfigure(0, weight=1) + file_frame.rowconfigure(1, weight=1) + + def toggle_settings(self): + if self.mode.get() == "audio_to_ogg": + self.loudnorm_frame.grid() + else: + self.loudnorm_frame.grid_remove() + + def select_files(self): + file_types = [ + ("音频文件", "*.wav *.mogg *.ogg *.flac") if self.mode.get() == "audio_to_ogg" + else ("ogg文件", "*.ogg") + ] + + files = filedialog.askopenfilenames(filetypes=file_types) + for f in files: + self.tree.insert("", tk.END, values=("[ ]", os.path.basename(f)), tags=(f,)) + + def on_tree_click(self, event): + """处理复选框点击事件""" + region = self.tree.identify("region", event.x, event.y) + if region == "cell": + col = self.tree.identify_column(event.x) + item = self.tree.identify_row(event.y) + if col == "#1": # 点击的是选中列 + current_val = self.tree.item(item, "values")[0] + new_val = "[√]" if current_val == "[ ]" else "[ ]" + self.tree.item(item, values=(new_val, self.tree.item(item, "values")[1])) + + def remove_selected(self): + """移除选中的文件""" + to_remove = [] + for item in self.tree.get_children(): + if self.tree.item(item, "values")[0] == "[√]": + to_remove.append(item) + for item in reversed(to_remove): + self.tree.delete(item) + + def clear_files(self): + """清空所有文件""" + for item in self.tree.get_children(): + self.tree.delete(item) + + def select_output_dir(self): + path = filedialog.askdirectory() + if path: + self.output_dir.set(path) + + def redirect_output(self): + class StdoutRedirector: + def __init__(self, text_widget): + self.text_widget = text_widget + self.original_stdout = sys.stdout + + def write(self, message): + self.text_widget.insert(tk.END, message) + self.text_widget.see(tk.END) + self.original_stdout.write(message) + + def flush(self): + self.original_stdout.flush() + + sys.stdout = StdoutRedirector(self.log_text) + + def start_conversion(self, convert_all): + """开始转换""" + input_files = [] + for item in self.tree.get_children(): + if convert_all or self.tree.item(item, "values")[0] == "[√]": + input_files.append(self.tree.item(item, "tags")[0]) + + if not input_files: + msg = "没有找到可转换的文件" if convert_all else "没有选中任何文件" + messagebox.showwarning("警告", msg) + return + + os.makedirs(self.output_dir.get(), exist_ok=True) + + try: + if self.mode.get() == "audio_to_ogg": + target_lufs = self.target_lufs.get() if self.enable_loudnorm.get() else None + thread = threading.Thread(target=self.convert_audio_to_ogg, args=(target_lufs, input_files)) + else: + thread = threading.Thread(target=self.convert_ogg_to_audio, args=(input_files,)) + + thread.start() + except Exception as e: + print(f"转换初始化失败: {str(e)}") + + def convert_audio_to_ogg(self, target_lufs, input_files): + """音频转到ogg转换逻辑""" + for input_path in input_files: + try: + filename = os.path.basename(input_path) + base_name = os.path.splitext(filename)[0] + output_path = os.path.join(self.output_dir.get(), f"{base_name}.ogg") + + print(f"正在转换: {filename}") + ( + ffmpeg + .input(input_path) + .output(output_path, acodec='libopus', audio_bitrate='16k', ac=1, ar=16000, frame_duration=60) + .run(overwrite_output=True) + ) + print(f"转换成功: {filename}\n") + except Exception as e: + print(f"转换失败: {str(e)}\n") + + def convert_ogg_to_audio(self, input_files): + """ogg转回音频转换逻辑""" + for input_path in input_files: + try: + filename = os.path.basename(input_path) + base_name = os.path.splitext(filename)[0] + output_path = os.path.join(self.output_dir.get(), f"{base_name}.ogg") + + print(f"正在转换: {filename}") + ( + ffmpeg + .input(input_path) + .output(output_path, acodec='libopus', audio_bitrate='16k', ac=1, ar=16000, frame_duration=60) + .run(overwrite_output=True) + ) + print(f"转换成功: {filename}\n") + except Exception as e: + print(f"转换失败: {str(e)}\n") + +if __name__ == "__main__": + root = tk.Tk() + app = AudioConverterApp(root) + root.mainloop() diff --git a/scripts/p3_tools/README.md b/scripts/p3_tools/README.md new file mode 100644 index 0000000..0ee279c --- /dev/null +++ b/scripts/p3_tools/README.md @@ -0,0 +1,95 @@ +# P3音频格式转换与播放工具 + +这个目录包含两个用于处理P3格式音频文件的Python脚本: + +## 1. 音频转换工具 (convert_audio_to_p3.py) + +将普通音频文件转换为P3格式(4字节header + Opus数据包的流式结构)并进行响度标准化。 + +### 使用方法 + +```bash +python convert_audio_to_p3.py <输入音频文件> <输出P3文件> [-l LUFS] [-d] +``` + +其中,可选选项 `-l` 用于指定响度标准化的目标响度,默认为 -16 LUFS;可选选项 `-d` 可以禁用响度标准化。 + +如果输入的音频文件符合下面的任一条件,建议使用 `-d` 禁用响度标准化: +- 音频过短 +- 音频已经调整过响度 +- 音频来自默认 TTS (小智当前使用的 TTS 的默认响度已是 -16 LUFS) + +例如: +```bash +python convert_audio_to_p3.py input.mp3 output.p3 +``` + +## 2. P3音频播放工具 (play_p3.py) + +播放P3格式的音频文件。 + +### 特性 + +- 解码并播放P3格式的音频文件 +- 在播放结束或用户中断时应用淡出效果,避免破音 +- 支持通过命令行参数指定要播放的文件 + +### 使用方法 + +```bash +python play_p3.py +``` + +例如: +```bash +python play_p3.py output.p3 +``` + +## 3. 音频转回工具 (convert_p3_to_audio.py) + +将P3格式转换回普通音频文件。 + +### 使用方法 + +```bash +python convert_p3_to_audio.py <输入P3文件> <输出音频文件> +``` + +输出音频文件需要有扩展名。 + +例如: +```bash +python convert_p3_to_audio.py input.p3 output.wav +``` +## 4. 音频/P3批量转换工具 + +一个图形化的工具,支持批量转换音频到P3,P3到音频 + +![](./img/img.png) + +### 使用方法: +```bash +python batch_convert_gui.py +``` + +## 依赖安装 + +在使用这些脚本前,请确保安装了所需的Python库: + +```bash +pip install librosa opuslib numpy tqdm sounddevice pyloudnorm soundfile +``` + +或者使用提供的requirements.txt文件: + +```bash +pip install -r requirements.txt +``` + +## P3格式说明 + +P3格式是一种简单的流式音频格式,结构如下: +- 每个音频帧由一个4字节的头部和一个Opus编码的数据包组成 +- 头部格式:[1字节类型, 1字节保留, 2字节长度] +- 采样率固定为16000Hz,单声道 +- 每帧时长为60ms \ No newline at end of file diff --git a/scripts/p3_tools/batch_convert_gui.py b/scripts/p3_tools/batch_convert_gui.py new file mode 100644 index 0000000..8555e55 --- /dev/null +++ b/scripts/p3_tools/batch_convert_gui.py @@ -0,0 +1,221 @@ +import tkinter as tk +from tkinter import ttk, filedialog, messagebox +import os +import threading +import sys +from convert_audio_to_p3 import encode_audio_to_opus +from convert_p3_to_audio import decode_p3_to_audio + +class AudioConverterApp: + def __init__(self, master): + self.master = master + master.title("音频/P3 批量转换工具") + master.geometry("680x600") # 调整窗口高度 + + # 初始化变量 + self.mode = tk.StringVar(value="audio_to_p3") + self.output_dir = tk.StringVar() + self.output_dir.set(os.path.abspath("output")) + self.enable_loudnorm = tk.BooleanVar(value=True) + self.target_lufs = tk.DoubleVar(value=-16.0) + + # 创建UI组件 + self.create_widgets() + self.redirect_output() + + def create_widgets(self): + # 模式选择 + mode_frame = ttk.LabelFrame(self.master, text="转换模式") + mode_frame.grid(row=0, column=0, padx=10, pady=5, sticky="ew") + + ttk.Radiobutton(mode_frame, text="音频转P3", variable=self.mode, + value="audio_to_p3", command=self.toggle_settings, + width=12).grid(row=0, column=0, padx=5) + ttk.Radiobutton(mode_frame, text="P3转音频", variable=self.mode, + value="p3_to_audio", command=self.toggle_settings, + width=12).grid(row=0, column=1, padx=5) + + # 响度设置 + self.loudnorm_frame = ttk.Frame(self.master) + self.loudnorm_frame.grid(row=1, column=0, padx=10, pady=5, sticky="ew") + + ttk.Checkbutton(self.loudnorm_frame, text="启用响度调整", + variable=self.enable_loudnorm, width=15 + ).grid(row=0, column=0, padx=2) + ttk.Entry(self.loudnorm_frame, textvariable=self.target_lufs, + width=6).grid(row=0, column=1, padx=2) + ttk.Label(self.loudnorm_frame, text="LUFS").grid(row=0, column=2, padx=2) + + # 文件选择 + file_frame = ttk.LabelFrame(self.master, text="输入文件") + file_frame.grid(row=2, column=0, padx=10, pady=5, sticky="nsew") + + # 文件操作按钮 + ttk.Button(file_frame, text="选择文件", command=self.select_files, + width=12).grid(row=0, column=0, padx=5, pady=2) + ttk.Button(file_frame, text="移除选中", command=self.remove_selected, + width=12).grid(row=0, column=1, padx=5, pady=2) + ttk.Button(file_frame, text="清空列表", command=self.clear_files, + width=12).grid(row=0, column=2, padx=5, pady=2) + + # 文件列表(使用Treeview) + self.tree = ttk.Treeview(file_frame, columns=("selected", "filename"), + show="headings", height=8) + self.tree.heading("selected", text="选中", anchor=tk.W) + self.tree.heading("filename", text="文件名", anchor=tk.W) + self.tree.column("selected", width=60, anchor=tk.W) + self.tree.column("filename", width=600, anchor=tk.W) + self.tree.grid(row=1, column=0, columnspan=3, sticky="nsew", padx=5, pady=2) + self.tree.bind("", self.on_tree_click) + + # 输出目录 + output_frame = ttk.LabelFrame(self.master, text="输出目录") + output_frame.grid(row=3, column=0, padx=10, pady=5, sticky="ew") + + ttk.Entry(output_frame, textvariable=self.output_dir, width=60 + ).grid(row=0, column=0, padx=5, sticky="ew") + ttk.Button(output_frame, text="浏览", command=self.select_output_dir, + width=8).grid(row=0, column=1, padx=5) + + # 转换按钮区域 + button_frame = ttk.Frame(self.master) + button_frame.grid(row=4, column=0, padx=10, pady=10, sticky="ew") + + ttk.Button(button_frame, text="转换全部文件", command=lambda: self.start_conversion(True), + width=15).pack(side=tk.LEFT, padx=5) + ttk.Button(button_frame, text="转换选中文件", command=lambda: self.start_conversion(False), + width=15).pack(side=tk.LEFT, padx=5) + + # 日志区域 + log_frame = ttk.LabelFrame(self.master, text="日志") + log_frame.grid(row=5, column=0, padx=10, pady=5, sticky="nsew") + + self.log_text = tk.Text(log_frame, height=14, width=80) + self.log_text.pack(fill=tk.BOTH, expand=True) + + # 配置布局权重 + self.master.columnconfigure(0, weight=1) + self.master.rowconfigure(2, weight=1) + self.master.rowconfigure(5, weight=3) + file_frame.columnconfigure(0, weight=1) + file_frame.rowconfigure(1, weight=1) + + def toggle_settings(self): + if self.mode.get() == "audio_to_p3": + self.loudnorm_frame.grid() + else: + self.loudnorm_frame.grid_remove() + + def select_files(self): + file_types = [ + ("音频文件", "*.wav *.mp3 *.ogg *.flac") if self.mode.get() == "audio_to_p3" + else ("P3文件", "*.p3") + ] + + files = filedialog.askopenfilenames(filetypes=file_types) + for f in files: + self.tree.insert("", tk.END, values=("[ ]", os.path.basename(f)), tags=(f,)) + + def on_tree_click(self, event): + """处理复选框点击事件""" + region = self.tree.identify("region", event.x, event.y) + if region == "cell": + col = self.tree.identify_column(event.x) + item = self.tree.identify_row(event.y) + if col == "#1": # 点击的是选中列 + current_val = self.tree.item(item, "values")[0] + new_val = "[√]" if current_val == "[ ]" else "[ ]" + self.tree.item(item, values=(new_val, self.tree.item(item, "values")[1])) + + def remove_selected(self): + """移除选中的文件""" + to_remove = [] + for item in self.tree.get_children(): + if self.tree.item(item, "values")[0] == "[√]": + to_remove.append(item) + for item in reversed(to_remove): + self.tree.delete(item) + + def clear_files(self): + """清空所有文件""" + for item in self.tree.get_children(): + self.tree.delete(item) + + def select_output_dir(self): + path = filedialog.askdirectory() + if path: + self.output_dir.set(path) + + def redirect_output(self): + class StdoutRedirector: + def __init__(self, text_widget): + self.text_widget = text_widget + self.original_stdout = sys.stdout + + def write(self, message): + self.text_widget.insert(tk.END, message) + self.text_widget.see(tk.END) + self.original_stdout.write(message) + + def flush(self): + self.original_stdout.flush() + + sys.stdout = StdoutRedirector(self.log_text) + + def start_conversion(self, convert_all): + """开始转换""" + input_files = [] + for item in self.tree.get_children(): + if convert_all or self.tree.item(item, "values")[0] == "[√]": + input_files.append(self.tree.item(item, "tags")[0]) + + if not input_files: + msg = "没有找到可转换的文件" if convert_all else "没有选中任何文件" + messagebox.showwarning("警告", msg) + return + + os.makedirs(self.output_dir.get(), exist_ok=True) + + try: + if self.mode.get() == "audio_to_p3": + target_lufs = self.target_lufs.get() if self.enable_loudnorm.get() else None + thread = threading.Thread(target=self.convert_audio_to_p3, args=(target_lufs, input_files)) + else: + thread = threading.Thread(target=self.convert_p3_to_audio, args=(input_files,)) + + thread.start() + except Exception as e: + print(f"转换初始化失败: {str(e)}") + + def convert_audio_to_p3(self, target_lufs, input_files): + """音频转P3转换逻辑""" + for input_path in input_files: + try: + filename = os.path.basename(input_path) + base_name = os.path.splitext(filename)[0] + output_path = os.path.join(self.output_dir.get(), f"{base_name}.p3") + + print(f"正在转换: {filename}") + encode_audio_to_opus(input_path, output_path, target_lufs) + print(f"转换成功: {filename}\n") + except Exception as e: + print(f"转换失败: {str(e)}\n") + + def convert_p3_to_audio(self, input_files): + """P3转音频转换逻辑""" + for input_path in input_files: + try: + filename = os.path.basename(input_path) + base_name = os.path.splitext(filename)[0] + output_path = os.path.join(self.output_dir.get(), f"{base_name}.wav") + + print(f"正在转换: {filename}") + decode_p3_to_audio(input_path, output_path) + print(f"转换成功: {filename}\n") + except Exception as e: + print(f"转换失败: {str(e)}\n") + +if __name__ == "__main__": + root = tk.Tk() + app = AudioConverterApp(root) + root.mainloop() \ No newline at end of file diff --git a/scripts/p3_tools/convert_audio_to_p3.py b/scripts/p3_tools/convert_audio_to_p3.py new file mode 100644 index 0000000..519d662 --- /dev/null +++ b/scripts/p3_tools/convert_audio_to_p3.py @@ -0,0 +1,62 @@ +# convert audio files to protocol v3 stream +import librosa +import opuslib +import struct +import sys +import tqdm +import numpy as np +import argparse +import pyloudnorm as pyln + +def encode_audio_to_opus(input_file, output_file, target_lufs=None): + # Load audio file using librosa + audio, sample_rate = librosa.load(input_file, sr=None, mono=False, dtype=np.float32) + + # Convert to mono if stereo + if audio.ndim == 2: + audio = librosa.to_mono(audio) + + if target_lufs is not None: + print("Note: Automatic loudness adjustment is enabled, which may cause", file=sys.stderr) + print(" audio distortion. If the input audio has already been ", file=sys.stderr) + print(" loudness-adjusted or if the input audio is TTS audio, ", file=sys.stderr) + print(" please use the `-d` parameter to disable loudness adjustment.", file=sys.stderr) + meter = pyln.Meter(sample_rate) + current_loudness = meter.integrated_loudness(audio) + audio = pyln.normalize.loudness(audio, current_loudness, target_lufs) + print(f"Adjusted loudness: {current_loudness:.1f} LUFS -> {target_lufs} LUFS") + + # Convert sample rate to 16000Hz if necessary + target_sample_rate = 16000 + if sample_rate != target_sample_rate: + audio = librosa.resample(audio, orig_sr=sample_rate, target_sr=target_sample_rate) + sample_rate = target_sample_rate + + # Convert audio data back to int16 after processing + audio = (audio * 32767).astype(np.int16) + + # Initialize Opus encoder + encoder = opuslib.Encoder(sample_rate, 1, opuslib.APPLICATION_AUDIO) + + # Encode and save + with open(output_file, 'wb') as f: + duration = 60 # 60ms per frame + frame_size = int(sample_rate * duration / 1000) + for i in tqdm.tqdm(range(0, len(audio) - frame_size, frame_size)): + frame = audio[i:i + frame_size] + opus_data = encoder.encode(frame.tobytes(), frame_size=frame_size) + packet = struct.pack('>BBH', 0, 0, len(opus_data)) + opus_data + f.write(packet) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Convert audio to Opus with loudness normalization') + parser.add_argument('input_file', help='Input audio file') + parser.add_argument('output_file', help='Output .opus file') + parser.add_argument('-l', '--lufs', type=float, default=-16.0, + help='Target loudness in LUFS (default: -16)') + parser.add_argument('-d', '--disable-loudnorm', action='store_true', + help='Disable loudness normalization') + args = parser.parse_args() + + target_lufs = None if args.disable_loudnorm else args.lufs + encode_audio_to_opus(args.input_file, args.output_file, target_lufs) \ No newline at end of file diff --git a/scripts/p3_tools/convert_p3_to_audio.py b/scripts/p3_tools/convert_p3_to_audio.py new file mode 100644 index 0000000..f870b01 --- /dev/null +++ b/scripts/p3_tools/convert_p3_to_audio.py @@ -0,0 +1,51 @@ +import struct +import sys +import opuslib +import numpy as np +from tqdm import tqdm +import soundfile as sf + + +def decode_p3_to_audio(input_file, output_file): + sample_rate = 16000 + channels = 1 + decoder = opuslib.Decoder(sample_rate, channels) + + pcm_frames = [] + frame_size = int(sample_rate * 60 / 1000) + + with open(input_file, "rb") as f: + f.seek(0, 2) + total_size = f.tell() + f.seek(0) + + with tqdm(total=total_size, unit="B", unit_scale=True) as pbar: + while True: + header = f.read(4) + if not header or len(header) < 4: + break + + pkt_type, reserved, opus_len = struct.unpack(">BBH", header) + opus_data = f.read(opus_len) + if len(opus_data) != opus_len: + break + + pcm = decoder.decode(opus_data, frame_size) + pcm_frames.append(np.frombuffer(pcm, dtype=np.int16)) + + pbar.update(4 + opus_len) + + if not pcm_frames: + raise ValueError("No valid audio data found") + + pcm_data = np.concatenate(pcm_frames) + + sf.write(output_file, pcm_data, sample_rate, subtype="PCM_16") + + +if __name__ == "__main__": + if len(sys.argv) != 3: + print("Usage: python convert_p3_to_audio.py ") + sys.exit(1) + + decode_p3_to_audio(sys.argv[1], sys.argv[2]) diff --git a/scripts/p3_tools/img/img.png b/scripts/p3_tools/img/img.png new file mode 100644 index 0000000..7ee34ee Binary files /dev/null and b/scripts/p3_tools/img/img.png differ diff --git a/scripts/p3_tools/p3_gui_player.py b/scripts/p3_tools/p3_gui_player.py new file mode 100644 index 0000000..3bbc8a3 --- /dev/null +++ b/scripts/p3_tools/p3_gui_player.py @@ -0,0 +1,241 @@ +import tkinter as tk +from tkinter import filedialog, messagebox +import threading +import time +import opuslib +import struct +import numpy as np +import sounddevice as sd +import os + + +def play_p3_file(input_file, stop_event=None, pause_event=None): + """ + 播放p3格式的音频文件 + p3格式: [1字节类型, 1字节保留, 2字节长度, Opus数据] + """ + # 初始化Opus解码器 + sample_rate = 16000 # 采样率固定为16000Hz + channels = 1 # 单声道 + decoder = opuslib.Decoder(sample_rate, channels) + + # 帧大小 (60ms) + frame_size = int(sample_rate * 60 / 1000) + + # 打开音频流 + stream = sd.OutputStream( + samplerate=sample_rate, + channels=channels, + dtype='int16' + ) + stream.start() + + try: + with open(input_file, 'rb') as f: + print(f"正在播放: {input_file}") + + while True: + if stop_event and stop_event.is_set(): + break + + if pause_event and pause_event.is_set(): + time.sleep(0.1) + continue + + # 读取头部 (4字节) + header = f.read(4) + if not header or len(header) < 4: + break + + # 解析头部 + packet_type, reserved, data_len = struct.unpack('>BBH', header) + + # 读取Opus数据 + opus_data = f.read(data_len) + if not opus_data or len(opus_data) < data_len: + break + + # 解码Opus数据 + pcm_data = decoder.decode(opus_data, frame_size) + + # 将字节转换为numpy数组 + audio_array = np.frombuffer(pcm_data, dtype=np.int16) + + # 播放音频 + stream.write(audio_array) + + except KeyboardInterrupt: + print("\n播放已停止") + finally: + stream.stop() + stream.close() + print("播放完成") + + +class P3PlayerApp: + def __init__(self, root): + self.root = root + self.root.title("P3 文件简易播放器") + self.root.geometry("500x400") + + self.playlist = [] + self.current_index = 0 + self.is_playing = False + self.is_paused = False + self.stop_event = threading.Event() + self.pause_event = threading.Event() + self.loop_playback = tk.BooleanVar(value=False) # 循环播放复选框的状态 + + # 创建界面组件 + self.create_widgets() + + def create_widgets(self): + # 播放列表 + self.playlist_label = tk.Label(self.root, text="播放列表:") + self.playlist_label.pack(pady=5) + + self.playlist_frame = tk.Frame(self.root) + self.playlist_frame.pack(fill=tk.BOTH, expand=True, padx=10, pady=5) + + self.playlist_listbox = tk.Listbox(self.playlist_frame, selectmode=tk.SINGLE) + self.playlist_listbox.pack(fill=tk.BOTH, expand=True) + + # 复选框和移除按钮 + self.checkbox_frame = tk.Frame(self.root) + self.checkbox_frame.pack(pady=5) + + self.remove_button = tk.Button(self.checkbox_frame, text="移除文件", command=self.remove_files) + self.remove_button.pack(side=tk.LEFT, padx=5) + + # 循环播放复选框 + self.loop_checkbox = tk.Checkbutton(self.checkbox_frame, text="循环播放", variable=self.loop_playback) + self.loop_checkbox.pack(side=tk.LEFT, padx=5) + + # 控制按钮 + self.control_frame = tk.Frame(self.root) + self.control_frame.pack(pady=10) + + self.add_button = tk.Button(self.control_frame, text="添加文件", command=self.add_file) + self.add_button.grid(row=0, column=0, padx=5) + + self.play_button = tk.Button(self.control_frame, text="播放", command=self.play) + self.play_button.grid(row=0, column=1, padx=5) + + self.pause_button = tk.Button(self.control_frame, text="暂停", command=self.pause) + self.pause_button.grid(row=0, column=2, padx=5) + + self.stop_button = tk.Button(self.control_frame, text="停止", command=self.stop) + self.stop_button.grid(row=0, column=3, padx=5) + + # 状态标签 + self.status_label = tk.Label(self.root, text="未在播放", fg="blue") + self.status_label.pack(pady=10) + + def add_file(self): + files = filedialog.askopenfilenames(filetypes=[("P3 文件", "*.p3")]) + if files: + self.playlist.extend(files) + self.update_playlist() + + def update_playlist(self): + self.playlist_listbox.delete(0, tk.END) + for file in self.playlist: + self.playlist_listbox.insert(tk.END, os.path.basename(file)) # 仅显示文件名 + + def update_status(self, status_text, color="blue"): + """更新状态标签的内容""" + self.status_label.config(text=status_text, fg=color) + + def play(self): + if not self.playlist: + messagebox.showwarning("警告", "播放列表为空!") + return + + if self.is_paused: + self.is_paused = False + self.pause_event.clear() + self.update_status(f"正在播放:{os.path.basename(self.playlist[self.current_index])}", "green") + return + + if self.is_playing: + return + + self.is_playing = True + self.stop_event.clear() + self.pause_event.clear() + self.current_index = self.playlist_listbox.curselection()[0] if self.playlist_listbox.curselection() else 0 + self.play_thread = threading.Thread(target=self.play_audio, daemon=True) + self.play_thread.start() + self.update_status(f"正在播放:{os.path.basename(self.playlist[self.current_index])}", "green") + + def play_audio(self): + while True: + if self.stop_event.is_set(): + break + + if self.pause_event.is_set(): + time.sleep(0.1) + continue + + # 检查当前索引是否有效 + if self.current_index >= len(self.playlist): + if self.loop_playback.get(): # 如果勾选了循环播放 + self.current_index = 0 # 回到第一首 + else: + break # 否则停止播放 + + file = self.playlist[self.current_index] + self.playlist_listbox.selection_clear(0, tk.END) + self.playlist_listbox.selection_set(self.current_index) + self.playlist_listbox.activate(self.current_index) + self.update_status(f"正在播放:{os.path.basename(self.playlist[self.current_index])}", "green") + play_p3_file(file, self.stop_event, self.pause_event) + + if self.stop_event.is_set(): + break + + if not self.loop_playback.get(): # 如果没有勾选循环播放 + break # 播放完当前文件后停止 + + self.current_index += 1 + if self.current_index >= len(self.playlist): + if self.loop_playback.get(): # 如果勾选了循环播放 + self.current_index = 0 # 回到第一首 + + self.is_playing = False + self.is_paused = False + self.update_status("播放已停止", "red") + + def pause(self): + if self.is_playing: + self.is_paused = not self.is_paused + if self.is_paused: + self.pause_event.set() + self.update_status("播放已暂停", "orange") + else: + self.pause_event.clear() + self.update_status(f"正在播放:{os.path.basename(self.playlist[self.current_index])}", "green") + + def stop(self): + if self.is_playing or self.is_paused: + self.is_playing = False + self.is_paused = False + self.stop_event.set() + self.pause_event.clear() + self.update_status("播放已停止", "red") + + def remove_files(self): + selected_indices = self.playlist_listbox.curselection() + if not selected_indices: + messagebox.showwarning("警告", "请先选择要移除的文件!") + return + + for index in reversed(selected_indices): + self.playlist.pop(index) + self.update_playlist() + + +if __name__ == "__main__": + root = tk.Tk() + app = P3PlayerApp(root) + root.mainloop() diff --git a/scripts/p3_tools/play_p3.py b/scripts/p3_tools/play_p3.py new file mode 100644 index 0000000..3c9ec81 --- /dev/null +++ b/scripts/p3_tools/play_p3.py @@ -0,0 +1,71 @@ +# 播放p3格式的音频文件 +import opuslib +import struct +import numpy as np +import sounddevice as sd +import argparse + +def play_p3_file(input_file): + """ + 播放p3格式的音频文件 + p3格式: [1字节类型, 1字节保留, 2字节长度, Opus数据] + """ + # 初始化Opus解码器 + sample_rate = 16000 # 采样率固定为16000Hz + channels = 1 # 单声道 + decoder = opuslib.Decoder(sample_rate, channels) + + # 帧大小 (60ms) + frame_size = int(sample_rate * 60 / 1000) + + # 打开音频流 + stream = sd.OutputStream( + samplerate=sample_rate, + channels=channels, + dtype='int16' + ) + stream.start() + + try: + with open(input_file, 'rb') as f: + print(f"正在播放: {input_file}") + + while True: + # 读取头部 (4字节) + header = f.read(4) + if not header or len(header) < 4: + break + + # 解析头部 + packet_type, reserved, data_len = struct.unpack('>BBH', header) + + # 读取Opus数据 + opus_data = f.read(data_len) + if not opus_data or len(opus_data) < data_len: + break + + # 解码Opus数据 + pcm_data = decoder.decode(opus_data, frame_size) + + # 将字节转换为numpy数组 + audio_array = np.frombuffer(pcm_data, dtype=np.int16) + + # 播放音频 + stream.write(audio_array) + + except KeyboardInterrupt: + print("\n播放已停止") + finally: + stream.stop() + stream.close() + print("播放完成") + +def main(): + parser = argparse.ArgumentParser(description='播放p3格式的音频文件') + parser.add_argument('input_file', help='输入的p3文件路径') + args = parser.parse_args() + + play_p3_file(args.input_file) + +if __name__ == "__main__": + main() diff --git a/scripts/p3_tools/requirements.txt b/scripts/p3_tools/requirements.txt new file mode 100644 index 0000000..d76d4cd --- /dev/null +++ b/scripts/p3_tools/requirements.txt @@ -0,0 +1,7 @@ +librosa>=0.9.2 +opuslib>=3.0.1 +numpy>=1.20.0 +tqdm>=4.62.0 +sounddevice>=0.4.4 +pyloudnorm>=0.1.1 +soundfile>=0.13.1 diff --git a/scripts/release.py b/scripts/release.py new file mode 100755 index 0000000..d1a3447 --- /dev/null +++ b/scripts/release.py @@ -0,0 +1,262 @@ +import sys +import os +import json +import zipfile +import argparse +from pathlib import Path +from typing import Optional + +# Switch to project root directory +os.chdir(Path(__file__).resolve().parent.parent) + +################################################################################ +# Common utility functions +################################################################################ + +def get_board_type_from_compile_commands() -> Optional[str]: + """Parse the current compiled BOARD_TYPE from build/compile_commands.json""" + compile_file = Path("build/compile_commands.json") + if not compile_file.exists(): + return None + with compile_file.open() as f: + data = json.load(f) + for item in data: + if not item["file"].endswith("main.cc"): + continue + cmd = item["command"] + if "-DBOARD_TYPE=\\\"" in cmd: + return cmd.split("-DBOARD_TYPE=\\\"")[1].split("\\\"")[0].strip() + return None + + +def get_project_version() -> Optional[str]: + """Read set(PROJECT_VER "x.y.z") from root CMakeLists.txt""" + with Path("CMakeLists.txt").open() as f: + for line in f: + if line.startswith("set(PROJECT_VER"): + return line.split("\"")[1] + return None + + +def merge_bin() -> None: + if os.system("idf.py merge-bin") != 0: + print("merge-bin failed", file=sys.stderr) + sys.exit(1) + + +def zip_bin(name: str, version: str) -> None: + """Zip build/merged-binary.bin to releases/v{version}_{name}.zip""" + out_dir = Path("releases") + out_dir.mkdir(exist_ok=True) + output_path = out_dir / f"v{version}_{name}.zip" + + if output_path.exists(): + output_path.unlink() + + with zipfile.ZipFile(output_path, "w", compression=zipfile.ZIP_DEFLATED) as zipf: + zipf.write("build/merged-binary.bin", arcname="merged-binary.bin") + print(f"zip bin to {output_path} done") + +################################################################################ +# board / variant related functions +################################################################################ + +_BOARDS_DIR = Path("main/boards") + + +def _collect_variants(config_filename: str = "config.json") -> list[dict[str, str]]: + """Traverse all boards under main/boards, collect variant information. + + Return example: + [{"board": "bread-compact-ml307", "name": "bread-compact-ml307"}, ...] + """ + variants: list[dict[str, str]] = [] + for board_path in _BOARDS_DIR.iterdir(): + if not board_path.is_dir(): + continue + if board_path.name == "common": + continue + cfg_path = board_path / config_filename + if not cfg_path.exists(): + print(f"[WARN] {cfg_path} does not exist, skip", file=sys.stderr) + continue + try: + with cfg_path.open() as f: + cfg = json.load(f) + for build in cfg.get("builds", []): + variants.append({"board": board_path.name, "name": build["name"]}) + except Exception as e: + print(f"[ERROR] 解析 {cfg_path} 失败: {e}", file=sys.stderr) + return variants + + +def _parse_board_config_map() -> dict[str, str]: + """Build the mapping of CONFIG_BOARD_TYPE_xxx and board_type from main/CMakeLists.txt""" + cmake_file = Path("main/CMakeLists.txt") + mapping: dict[str, str] = {} + lines = cmake_file.read_text(encoding="utf-8").splitlines() + for idx, line in enumerate(lines): + if "if(CONFIG_BOARD_TYPE_" in line: + config_name = line.strip().split("if(")[1].split(")")[0] + if idx + 1 < len(lines): + next_line = lines[idx + 1].strip() + if next_line.startswith("set(BOARD_TYPE"): + board_type = next_line.split('"')[1] + mapping[config_name] = board_type + return mapping + + +def _find_board_config(board_type: str) -> Optional[str]: + """Find the corresponding CONFIG_BOARD_TYPE_xxx for the given board_type""" + for config, b_type in _parse_board_config_map().items(): + if b_type == board_type: + return config + return None + +################################################################################ +# Check board_type in CMakeLists +################################################################################ + +def _board_type_exists(board_type: str) -> bool: + cmake_file = Path("main/CMakeLists.txt") + pattern = f'set(BOARD_TYPE "{board_type}")' + return pattern in cmake_file.read_text(encoding="utf-8") + +################################################################################ +# Compile implementation +################################################################################ + +def release(board_type: str, config_filename: str = "config.json", *, filter_name: Optional[str] = None) -> None: + """Compile and package all/specified variants of the specified board_type + + Args: + board_type: directory name under main/boards + config_filename: config.json name (default: config.json) + filter_name: if specified, only compile the build["name"] that matches + """ + cfg_path = _BOARDS_DIR / board_type / config_filename + if not cfg_path.exists(): + print(f"[WARN] {cfg_path} 不存在,跳过 {board_type}") + return + + project_version = get_project_version() + print(f"Project Version: {project_version} ({cfg_path})") + + with cfg_path.open() as f: + cfg = json.load(f) + target = cfg["target"] + + builds = cfg.get("builds", []) + if filter_name: + builds = [b for b in builds if b["name"] == filter_name] + if not builds: + print(f"[ERROR] 未在 {board_type} 的 {config_filename} 中找到变体 {filter_name}", file=sys.stderr) + sys.exit(1) + + for build in builds: + name = build["name"] + if not name.startswith(board_type): + raise ValueError(f"build.name {name} 必须以 {board_type} 开头") + + output_path = Path("releases") / f"v{project_version}_{name}.zip" + if output_path.exists(): + print(f"跳过 {name} 因为 {output_path} 已存在") + continue + + # Process sdkconfig_append + board_type_config = _find_board_config(board_type) + sdkconfig_append = [f"{board_type_config}=y"] + sdkconfig_append.extend(build.get("sdkconfig_append", [])) + + print("-" * 80) + print(f"name: {name}") + print(f"target: {target}") + for item in sdkconfig_append: + print(f"sdkconfig_append: {item}") + + os.environ.pop("IDF_TARGET", None) + + # Call set-target + if os.system(f"idf.py set-target {target}") != 0: + print("set-target failed", file=sys.stderr) + sys.exit(1) + + # Append sdkconfig + with Path("sdkconfig").open("a") as f: + f.write("\n") + f.write("# Append by release.py\n") + for append in sdkconfig_append: + f.write(f"{append}\n") + # Build with macro BOARD_NAME defined to name + if os.system(f"idf.py -DBOARD_NAME={name} -DBOARD_TYPE={board_type} build") != 0: + print("build failed") + sys.exit(1) + + # merge-bin + merge_bin() + + # Zip + zip_bin(name, project_version) + +################################################################################ +# CLI entry +################################################################################ + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("board", nargs="?", default=None, help="板子类型或 all") + parser.add_argument("-c", "--config", default="config.json", help="指定 config 文件名,默认 config.json") + parser.add_argument("--list-boards", action="store_true", help="列出所有支持的 board 及变体列表") + parser.add_argument("--json", action="store_true", help="配合 --list-boards,JSON 格式输出") + parser.add_argument("--name", help="指定变体名称,仅编译匹配的变体") + + args = parser.parse_args() + + # List mode + if args.list_boards: + variants = _collect_variants(config_filename=args.config) + if args.json: + print(json.dumps(variants)) + else: + for v in variants: + print(f"{v['board']}: {v['name']}") + sys.exit(0) + + # Current directory firmware packaging mode + if args.board is None: + merge_bin() + curr_board_type = get_board_type_from_compile_commands() + if curr_board_type is None: + print("未能从 compile_commands.json 解析 board_type", file=sys.stderr) + sys.exit(1) + project_ver = get_project_version() + zip_bin(curr_board_type, project_ver) + sys.exit(0) + + # Compile mode + board_type_input: str = args.board + name_filter: str | None = args.name + + # Check board_type in CMakeLists + if board_type_input != "all" and not _board_type_exists(board_type_input): + print(f"[ERROR] main/CMakeLists.txt 中未找到 board_type {board_type_input}", file=sys.stderr) + sys.exit(1) + + variants_all = _collect_variants(config_filename=args.config) + + # Filter board_type list + target_board_types: set[str] + if board_type_input == "all": + target_board_types = {v["board"] for v in variants_all} + else: + target_board_types = {board_type_input} + + for bt in sorted(target_board_types): + if not _board_type_exists(bt): + print(f"[ERROR] main/CMakeLists.txt 中未找到 board_type {bt}", file=sys.stderr) + sys.exit(1) + cfg_path = _BOARDS_DIR / bt / args.config + if bt == board_type_input and not cfg_path.exists(): + print(f"开发板 {bt} 未定义 {args.config} 配置文件,跳过") + sys.exit(0) + release(bt, config_filename=args.config, filter_name=name_filter if bt == board_type_input else None) diff --git a/scripts/sonic_wifi_config.html b/scripts/sonic_wifi_config.html new file mode 100644 index 0000000..b5c5093 --- /dev/null +++ b/scripts/sonic_wifi_config.html @@ -0,0 +1,208 @@ + + + + + 小智声波配网 + + + + +
+

📶 小智声波配网

+ + + + + + +
+ +
+ + + + +
+ + + + diff --git a/scripts/spiffs_assets/README.md b/scripts/spiffs_assets/README.md new file mode 100644 index 0000000..9cd0f92 --- /dev/null +++ b/scripts/spiffs_assets/README.md @@ -0,0 +1,110 @@ +# SPIFFS Assets Builder + +这个脚本用于构建 ESP32 项目的 SPIFFS 资源分区,将各种资源文件打包成可在设备上使用的格式。 + +## 功能特性 + +- 处理唤醒网络模型 (WakeNet Model) +- 集成文本字体文件 +- 处理表情符号图片集合 +- 自动生成资源索引文件 +- 打包生成最终的 `assets.bin` 文件 + +## 依赖要求 + +- Python 3.6+ +- 相关资源文件 + +## 使用方法 + +### 基本语法 + +```bash +./build.py --wakenet_model \ + --text_font \ + --emoji_collection +``` + +### 参数说明 + +| 参数 | 类型 | 必需 | 说明 | +|------|------|------|------| +| `--wakenet_model` | 目录路径 | 否 | 唤醒网络模型目录路径 | +| `--text_font` | 文件路径 | 否 | 文本字体文件路径 | +| `--emoji_collection` | 目录路径 | 否 | 表情符号图片集合目录路径 | + +### 使用示例 + +```bash +# 完整参数示例 +./build.py \ + --wakenet_model ../../managed_components/espressif__esp-sr/model/wakenet_model/wn9_nihaoxiaozhi_tts \ + --text_font ../../components/xiaozhi-fonts/build/font_puhui_common_20_4.bin \ + --emoji_collection ../../components/xiaozhi-fonts/build/emojis_64/ + +# 仅处理字体文件 +./build.py --text_font ../../components/xiaozhi-fonts/build/font_puhui_common_20_4.bin + +# 仅处理表情符号 +./build.py --emoji_collection ../../components/xiaozhi-fonts/build/emojis_64/ +``` + +## 工作流程 + +1. **创建构建目录结构** + - `build/` - 主构建目录 + - `build/assets/` - 资源文件目录 + - `build/output/` - 输出文件目录 + +2. **处理唤醒网络模型** + - 复制模型文件到构建目录 + - 使用 `pack_model.py` 生成 `srmodels.bin` + - 将生成的模型文件复制到资源目录 + +3. **处理文本字体** + - 复制字体文件到资源目录 + - 支持 `.bin` 格式的字体文件 + +4. **处理表情符号集合** + - 扫描指定目录中的图片文件 + - 支持 `.png` 和 `.gif` 格式 + - 自动生成表情符号索引 + +5. **生成配置文件** + - `index.json` - 资源索引文件 + - `config.json` - 构建配置文件 + +6. **打包最终资源** + - 使用 `spiffs_assets_gen.py` 生成 `assets.bin` + - 复制到构建根目录 + +## 输出文件 + +构建完成后,会在 `build/` 目录下生成以下文件: + +- `assets/` - 所有资源文件 +- `assets.bin` - 最终的 SPIFFS 资源文件 +- `config.json` - 构建配置 +- `output/` - 中间输出文件 + +## 支持的资源格式 + +- **模型文件**: `.bin` (通过 pack_model.py 处理) +- **字体文件**: `.bin` +- **图片文件**: `.png`, `.gif` +- **配置文件**: `.json` + +## 错误处理 + +脚本包含完善的错误处理机制: + +- 检查源文件/目录是否存在 +- 验证子进程执行结果 +- 提供详细的错误信息和警告 + +## 注意事项 + +1. 确保所有依赖的 Python 脚本都在同一目录下 +2. 资源文件路径使用绝对路径或相对于脚本目录的路径 +3. 构建过程会清理之前的构建文件 +4. 生成的 `assets.bin` 文件大小受 SPIFFS 分区大小限制 diff --git a/scripts/spiffs_assets/build.py b/scripts/spiffs_assets/build.py new file mode 100644 index 0000000..47069d2 --- /dev/null +++ b/scripts/spiffs_assets/build.py @@ -0,0 +1,400 @@ +#!/usr/bin/env python3 +""" +Build the spiffs assets partition + +Usage: + ./build.py --wakenet_model \ + --text_font \ + --emoji_collection + +Example: + ./build.py --wakenet_model ../../managed_components/espressif__esp-sr/model/wakenet_model/wn9_nihaoxiaozhi_tts \ + --text_font ../../components/xiaozhi-fonts/build/font_puhui_common_20_4.bin \ + --emoji_collection ../../components/xiaozhi-fonts/build/emojis_64/ +""" + +import os +import sys +import shutil +import argparse +import subprocess +import json +from pathlib import Path + + +def ensure_dir(directory): + """Ensure directory exists, create if not""" + os.makedirs(directory, exist_ok=True) + + +def copy_file(src, dst): + """Copy file""" + if os.path.exists(src): + shutil.copy2(src, dst) + print(f"Copied: {src} -> {dst}") + else: + print(f"Warning: Source file does not exist: {src}") + + +def copy_directory(src, dst): + """Copy directory""" + if os.path.exists(src): + shutil.copytree(src, dst, dirs_exist_ok=True) + print(f"Copied directory: {src} -> {dst}") + else: + print(f"Warning: Source directory does not exist: {src}") + + +def process_wakenet_model(wakenet_model_dir, build_dir, assets_dir): + """Process wakenet_model parameter""" + if not wakenet_model_dir: + return None + + # Copy input directory to build directory + wakenet_build_dir = os.path.join(build_dir, "wakenet_model") + if os.path.exists(wakenet_build_dir): + shutil.rmtree(wakenet_build_dir) + copy_directory(wakenet_model_dir, os.path.join(wakenet_build_dir, os.path.basename(wakenet_model_dir))) + + # Use pack_model.py to generate srmodels.bin + srmodels_output = os.path.join(wakenet_build_dir, "srmodels.bin") + try: + subprocess.run([ + sys.executable, "pack_model.py", + "-m", wakenet_build_dir, + "-o", "srmodels.bin" + ], check=True, cwd=os.path.dirname(__file__)) + print(f"Generated: {srmodels_output}") + # Copy srmodels.bin to assets directory + copy_file(srmodels_output, os.path.join(assets_dir, "srmodels.bin")) + return "srmodels.bin" + except subprocess.CalledProcessError as e: + print(f"Error: Failed to generate srmodels.bin: {e}") + return None + + +def process_text_font(text_font_file, assets_dir): + """Process text_font parameter""" + if not text_font_file: + return None + + # Copy input file to build/assets directory + font_filename = os.path.basename(text_font_file) + font_dst = os.path.join(assets_dir, font_filename) + copy_file(text_font_file, font_dst) + + return font_filename + + +def process_emoji_collection(emoji_collection_dir, assets_dir): + """Process emoji_collection parameter""" + if not emoji_collection_dir: + return [] + + emoji_list = [] + + # Copy each image from input directory to build/assets directory + for root, dirs, files in os.walk(emoji_collection_dir): + for file in files: + if file.lower().endswith(('.png', '.gif')): + # Copy file + src_file = os.path.join(root, file) + dst_file = os.path.join(assets_dir, file) + copy_file(src_file, dst_file) + + # Get filename without extension + filename_without_ext = os.path.splitext(file)[0] + + # Add to emoji list + emoji_list.append({ + "name": filename_without_ext, + "file": file + }) + + return emoji_list + +def load_emoji_config(emoji_collection_dir): + """Load emoji config from config.json file""" + config_path = os.path.join(emoji_collection_dir, "emote.json") + if not os.path.exists(config_path): + print(f"Warning: Config file not found: {config_path}") + return {} + + try: + with open(config_path, 'r', encoding='utf-8') as f: + config_data = json.load(f) + + # Convert list format to dict for easy lookup + config_dict = {} + for item in config_data: + if "emote" in item: + config_dict[item["emote"]] = item + + return config_dict + except Exception as e: + print(f"Error loading config file {config_path}: {e}") + return {} + +def process_board_emoji_collection(emoji_collection_dir, target_board_dir, assets_dir): + """Process emoji_collection parameter""" + if not emoji_collection_dir: + return [] + + emoji_config = load_emoji_config(target_board_dir) + print(f"Loaded emoji config with {len(emoji_config)} entries") + + emoji_list = [] + + for emote_name, config in emoji_config.items(): + + if "src" not in config: + print(f"Error: No src field found for emote '{emote_name}' in config") + continue + + eaf_file_path = os.path.join(emoji_collection_dir, config["src"]) + file_exists = os.path.exists(eaf_file_path) + + if not file_exists: + print(f"Warning: EAF file not found for emote '{emote_name}': {eaf_file_path}") + else: + # Copy eaf file to assets directory + copy_file(eaf_file_path, os.path.join(assets_dir, config["src"])) + + # Create emoji entry with src as file (merge file and src) + emoji_entry = { + "name": emote_name, + "file": config["src"] # Use src as the actual file + } + + eaf_properties = {} + + if not file_exists: + eaf_properties["lack"] = True + + if "loop" in config: + eaf_properties["loop"] = config["loop"] + + if "fps" in config: + eaf_properties["fps"] = config["fps"] + + if eaf_properties: + emoji_entry["eaf"] = eaf_properties + + status = "MISSING" if not file_exists else "OK" + eaf_info = emoji_entry.get('eaf', {}) + print(f"emote '{emote_name}': file='{emoji_entry['file']}', status={status}, lack={eaf_info.get('lack', False)}, loop={eaf_info.get('loop', 'none')}, fps={eaf_info.get('fps', 'none')}") + + emoji_list.append(emoji_entry) + + print(f"Successfully processed {len(emoji_list)} emotes from config") + return emoji_list + +def process_board_icon_collection(icon_collection_dir, assets_dir): + """Process emoji_collection parameter""" + if not icon_collection_dir: + return [] + + icon_list = [] + + for root, dirs, files in os.walk(icon_collection_dir): + for file in files: + if file.lower().endswith(('.bin')) or file.lower() == 'listen.eaf': + src_file = os.path.join(root, file) + dst_file = os.path.join(assets_dir, file) + copy_file(src_file, dst_file) + + filename_without_ext = os.path.splitext(file)[0] + + icon_list.append({ + "name": filename_without_ext, + "file": file + }) + + return icon_list +def process_board_layout(layout_json_file, assets_dir): + """Process layout_json parameter""" + if not layout_json_file: + print(f"Warning: Layout json file not provided") + return [] + + print(f"Processing layout_json: {layout_json_file}") + print(f"assets_dir: {assets_dir}") + + if os.path.isdir(layout_json_file): + layout_json_path = os.path.join(layout_json_file, "layout.json") + if not os.path.exists(layout_json_path): + print(f"Warning: layout.json not found in directory: {layout_json_file}") + return [] + layout_json_file = layout_json_path + elif not os.path.isfile(layout_json_file): + print(f"Warning: Layout json file not found: {layout_json_file}") + return [] + + try: + with open(layout_json_file, 'r', encoding='utf-8') as f: + layout_data = json.load(f) + + # Layout data is now directly an array, no need to get "layout" key + layout_items = layout_data if isinstance(layout_data, list) else layout_data.get("layout", []) + + processed_layout = [] + for item in layout_items: + processed_item = { + "name": item.get("name", ""), + "align": item.get("align", ""), + "x": item.get("x", 0), + "y": item.get("y", 0) + } + + if "width" in item: + processed_item["width"] = item["width"] + if "height" in item: + processed_item["height"] = item["height"] + + processed_layout.append(processed_item) + + print(f"Processed {len(processed_layout)} layout elements") + return processed_layout + + except Exception as e: + print(f"Error reading/processing layout.json: {e}") + return [] + +def process_board_collection(target_board_dir, res_path, assets_dir): + """Process board collection - merge icon, emoji, and layout processing""" + + # Process all collections + if os.path.exists(res_path) and os.path.exists(target_board_dir): + emoji_collection = process_board_emoji_collection(res_path, target_board_dir, assets_dir) + icon_collection = process_board_icon_collection(res_path, assets_dir) + layout_json = process_board_layout(target_board_dir, assets_dir) + else: + print(f"Warning: EAF directory not found: {res_path} or {target_board_dir}") + emoji_collection = [] + icon_collection = [] + layout_json = [] + + return emoji_collection, icon_collection, layout_json + +def generate_index_json(assets_dir, srmodels, text_font, emoji_collection, icon_collection, layout_json): + """Generate index.json file""" + index_data = { + "version": 1 + } + + if srmodels: + index_data["srmodels"] = srmodels + + if text_font: + index_data["text_font"] = text_font + + if emoji_collection: + index_data["emoji_collection"] = emoji_collection + + if icon_collection: + index_data["icon_collection"] = icon_collection + + if layout_json: + index_data["layout"] = layout_json + + # Write index.json + index_path = os.path.join(assets_dir, "index.json") + with open(index_path, 'w', encoding='utf-8') as f: + json.dump(index_data, f, indent=4, ensure_ascii=False) + + print(f"Generated: {index_path}") + + +def generate_config_json(build_dir, assets_dir): + """Generate config.json file""" + # Get absolute path of current working directory + workspace_dir = os.path.abspath(os.path.join(os.path.dirname(__file__))) + + config_data = { + "include_path": os.path.join(workspace_dir, "build/include"), + "assets_path": os.path.join(workspace_dir, "build/assets"), + "image_file": os.path.join(workspace_dir, "build/output/assets.bin"), + "lvgl_ver": "9.3.0", + "assets_size": "0x400000", + "support_format": ".png, .gif, .jpg, .bin, .json, .eaf", + "name_length": "32", + "split_height": "0", + "support_qoi": False, + "support_spng": False, + "support_sjpg": False, + "support_sqoi": False, + "support_raw": False, + "support_raw_dither": False, + "support_raw_bgr": False + } + + # Write config.json + config_path = os.path.join(build_dir, "config.json") + with open(config_path, 'w', encoding='utf-8') as f: + json.dump(config_data, f, indent=4, ensure_ascii=False) + + print(f"Generated: {config_path}") + return config_path + + +def main(): + parser = argparse.ArgumentParser(description='Build the spiffs assets partition') + parser.add_argument('--wakenet_model', help='Path to wakenet model directory') + parser.add_argument('--text_font', help='Path to text font file') + parser.add_argument('--emoji_collection', help='Path to emoji collection directory') + + parser.add_argument('--res_path', help='Path to res directory') + parser.add_argument('--target_board', help='Path to target board directory') + + args = parser.parse_args() + + # Get script directory + script_dir = os.path.dirname(os.path.abspath(__file__)) + + # Set directory paths + build_dir = os.path.join(script_dir, "build") + assets_dir = os.path.join(build_dir, "assets") + if os.path.exists(assets_dir): + shutil.rmtree(assets_dir) + + # Ensure directories exist + ensure_dir(build_dir) + ensure_dir(assets_dir) + + print("Starting to build SPIFFS assets partition...") + + # Process each parameter + srmodels = process_wakenet_model(args.wakenet_model, build_dir, assets_dir) + text_font = process_text_font(args.text_font, assets_dir) + + if(args.target_board): + emoji_collection, icon_collection, layout_json = process_board_collection(args.target_board, args.res_path, assets_dir) + else: + emoji_collection = process_emoji_collection(args.emoji_collection, assets_dir) + icon_collection = [] + layout_json = [] + + # Generate index.json + generate_index_json(assets_dir, srmodels, text_font, emoji_collection, icon_collection, layout_json) + + # Generate config.json + config_path = generate_config_json(build_dir, assets_dir) + + # Use spiffs_assets_gen.py to package final build/assets.bin + try: + subprocess.run([ + sys.executable, "spiffs_assets_gen.py", + "--config", config_path + ], check=True, cwd=script_dir) + print("Successfully packaged assets.bin") + except subprocess.CalledProcessError as e: + print(f"Error: Failed to package assets.bin: {e}") + sys.exit(1) + + # Copy build/output/assets.bin to build/assets.bin + shutil.copy(os.path.join(build_dir, "output", "assets.bin"), os.path.join(build_dir, "assets.bin")) + print("Build completed!") + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/scripts/spiffs_assets/build_all.py b/scripts/spiffs_assets/build_all.py new file mode 100644 index 0000000..e812f8d --- /dev/null +++ b/scripts/spiffs_assets/build_all.py @@ -0,0 +1,187 @@ +#!/usr/bin/env python3 +""" +Build multiple spiffs assets partitions with different parameter combinations + +This script calls build.py with different combinations of: +- wakenet_models +- text_fonts +- emoji_collections + +And generates assets.bin files with names like: +wn9_nihaoxiaozhi_tts-font_puhui_common_20_4-emojis_32.bin +""" + +import os +import sys +import shutil +import subprocess +import argparse +from pathlib import Path + + +def ensure_dir(directory): + """Ensure directory exists, create if not""" + os.makedirs(directory, exist_ok=True) + + +def get_file_path(base_dir, filename): + """Get full path for a file, handling 'none' case""" + if filename == "none": + return None + return os.path.join(base_dir, f"{filename}.bin" if not filename.startswith("emojis_") else filename) + + +def build_assets(wakenet_model, text_font, emoji_collection, target_board, build_dir, final_dir): + """Build assets.bin using build.py with given parameters""" + + # Prepare arguments for build.py + cmd = [sys.executable, "build.py"] + + if wakenet_model != "none": + wakenet_path = os.path.join("../../managed_components/espressif__esp-sr/model/wakenet_model", wakenet_model) + cmd.extend(["--wakenet_model", wakenet_path]) + + if text_font != "none": + text_font_path = os.path.join("../../components/78__xiaozhi-fonts/cbin", f"{text_font}.bin") + cmd.extend(["--text_font", text_font_path]) + + if emoji_collection != "none": + emoji_path = os.path.join("../../components/xiaozhi-fonts/build", emoji_collection) + cmd.extend(["--emoji_collection", emoji_path]) + + if target_board != "none": + res_path = os.path.join("../../managed_components/espressif2022__esp_emote_gfx/emoji_large", "") + cmd.extend(["--res_path", res_path]) + + target_board_path = os.path.join("../../main/boards/", f"{target_board}") + cmd.extend(["--target_board", target_board_path]) + + print(f"\n正在构建: {wakenet_model}-{text_font}-{emoji_collection}-{target_board}") + print(f"执行命令: {' '.join(cmd)}") + + try: + # Run build.py + result = subprocess.run(cmd, check=True, cwd=os.path.dirname(__file__)) + + # Generate output filename + if(target_board != "none"): + output_name = f"{wakenet_model}-{text_font}-{target_board}.bin" + else: + output_name = f"{wakenet_model}-{text_font}-{emoji_collection}.bin" + + # Copy generated assets.bin to final directory with new name + src_path = os.path.join(build_dir, "assets.bin") + dst_path = os.path.join(final_dir, output_name) + + if os.path.exists(src_path): + shutil.copy2(src_path, dst_path) + print(f"✓ 成功生成: {output_name}") + return True + else: + print(f"✗ 错误: 未找到生成的 assets.bin 文件") + return False + + except subprocess.CalledProcessError as e: + print(f"✗ 构建失败: {e}") + return False + except Exception as e: + print(f"✗ 未知错误: {e}") + return False + + +def main(): + # Parse command line arguments + parser = argparse.ArgumentParser(description='构建多个 SPIFFS assets 分区') + parser.add_argument('--mode', + choices=['emoji_collections', 'emoji_target_boards'], + default='emoji_collections', + help='选择运行模式: emoji_collections 或 emoji_target_boards (默认: emoji_collections)') + + args = parser.parse_args() + + # Configuration + wakenet_models = [ + "none", + "wn9_nihaoxiaozhi_tts", + "wn9s_nihaoxiaozhi" + ] + + text_fonts = [ + "none", + "font_puhui_common_14_1", + "font_puhui_common_16_4", + "font_puhui_common_20_4", + "font_puhui_common_30_4", + ] + + emoji_collections = [ + "none", + "emojis_32", + "emojis_64", + ] + + emoji_target_boards = [ + "esp-box-3", + "echoear", + ] + + # Get script directory + script_dir = os.path.dirname(os.path.abspath(__file__)) + + # Set directory paths + build_dir = os.path.join(script_dir, "build") + final_dir = os.path.join(build_dir, "final") + + # Ensure directories exist + ensure_dir(build_dir) + ensure_dir(final_dir) + + print("开始构建多个 SPIFFS assets 分区...") + print(f"运行模式: {args.mode}") + print(f"输出目录: {final_dir}") + + # Track successful builds + successful_builds = 0 + + if args.mode == 'emoji_collections': + # Calculate total combinations for emoji_collections mode + total_combinations = len(wakenet_models) * len(text_fonts) * len(emoji_collections) + + # Build all combinations with emoji_collections + for wakenet_model in wakenet_models: + for text_font in text_fonts: + for emoji_collection in emoji_collections: + if build_assets(wakenet_model, text_font, emoji_collection, "none", build_dir, final_dir): + successful_builds += 1 + + elif args.mode == 'emoji_target_boards': + # Calculate total combinations for emoji_target_boards mode + total_combinations = len(wakenet_models) * len(text_fonts) * len(emoji_target_boards) + + # Build all combinations with emoji_target_boards + for wakenet_model in wakenet_models: + for text_font in text_fonts: + for emoji_target_board in emoji_target_boards: + if build_assets(wakenet_model, text_font, "none", emoji_target_board, build_dir, final_dir): + successful_builds += 1 + + print(f"\n构建完成!") + print(f"成功构建: {successful_builds}/{total_combinations}") + print(f"输出文件位置: {final_dir}") + + # List generated files + if os.path.exists(final_dir): + files = [f for f in os.listdir(final_dir) if f.endswith('.bin')] + if files: + print("\n生成的文件:") + for file in sorted(files): + file_size = os.path.getsize(os.path.join(final_dir, file)) + print(f" {file} ({file_size:,} bytes)") + else: + print("\n未找到生成的 .bin 文件") + + +if __name__ == "__main__": + main() + + diff --git a/scripts/spiffs_assets/pack_model.py b/scripts/spiffs_assets/pack_model.py new file mode 100644 index 0000000..1fc85aa --- /dev/null +++ b/scripts/spiffs_assets/pack_model.py @@ -0,0 +1,123 @@ +import os +import struct +import argparse + + +def struct_pack_string(string, max_len=None): + """ + pack string to binary data. + if max_len is None, max_len = len(string) + 1 + else len(string) < max_len, the left will be padded by struct.pack('x') + + string: input python string + max_len: output + """ + + if max_len == None : + max_len = len(string) + else: + assert len(string) <= max_len + + left_num = max_len - len(string) + out_bytes = None + for char in string: + if out_bytes == None: + out_bytes = struct.pack('b', ord(char)) + else: + out_bytes += struct.pack('b', ord(char)) + for i in range(left_num): + out_bytes += struct.pack('x') + return out_bytes + +def read_data(filename): + """ + Read binary data, like index and mndata + """ + data = None + with open(filename, "rb") as f: + data = f.read() + return data + +def pack_models(model_path, out_file="srmodels.bin"): + """ + Pack all models into one binary file by the following format: + { + model_num: int + model1_info: model_info_t + model2_info: model_info_t + ... + model1_index,model1_data,model1_MODEL_INFO + model1_index,model1_data,model1_MODEL_INFO + ... + }model_pack_t + + { + model_name: char[32] + file_number: int + file1_name: char[32] + file1_start: int + file1_len: int + file2_name: char[32] + file2_start: int // data_len = info_start - data_start + file2_len: int + ... + }model_info_t + + model_path: the path of models + out_file: the ouput binary filename + """ + + models = {} + file_num = 0 + model_num = 0 + for root, dirs, _ in os.walk(model_path): + for model_name in dirs: + models[model_name] = {} + model_dir = os.path.join(root, model_name) + model_num += 1 + for _, _, files in os.walk(model_dir): + for file_name in files: + file_num += 1 + file_path = os.path.join(model_dir, file_name) + models[model_name][file_name] = read_data(file_path) + + model_num = len(models) + header_len = 4 + model_num*(32+4) + file_num*(32+4+4) + out_bin = struct.pack('I', model_num) # model number + data_bin = None + for key in models: + model_bin = struct_pack_string(key, 32) # + model name + model_bin += struct.pack('I', len(models[key])) # + file number in this model + + for file_name in models[key]: + model_bin += struct_pack_string(file_name, 32) # + file name + if data_bin == None: + model_bin += struct.pack('I', header_len) + data_bin = models[key][file_name] + model_bin += struct.pack('I', len(models[key][file_name])) + # print(file_name, header_len, len(models[key][file_name]), len(data_bin)) + else: + model_bin += struct.pack('I', header_len+len(data_bin)) + # print(file_name, header_len+len(data_bin), len(models[key][file_name])) + data_bin += models[key][file_name] + model_bin += struct.pack('I', len(models[key][file_name])) + + out_bin += model_bin + assert len(out_bin) == header_len + if data_bin != None: + out_bin += data_bin + + out_file = os.path.join(model_path, out_file) + with open(out_file, "wb") as f: + f.write(out_bin) + + +if __name__ == "__main__": + # input parameter + parser = argparse.ArgumentParser(description='Model package tool') + parser.add_argument('-m', '--model_path', help="the path of model files") + parser.add_argument('-o', '--out_file', default="srmodels.bin", help="the path of binary file") + args = parser.parse_args() + + # convert(args.model_path, args.out_file) + pack_models(model_path=args.model_path, out_file=args.out_file) diff --git a/scripts/spiffs_assets/spiffs_assets_gen.py b/scripts/spiffs_assets/spiffs_assets_gen.py new file mode 100644 index 0000000..e07aaaa --- /dev/null +++ b/scripts/spiffs_assets/spiffs_assets_gen.py @@ -0,0 +1,647 @@ +# SPDX-FileCopyrightText: 2024-2025 Espressif Systems (Shanghai) CO LTD +# SPDX-License-Identifier: Apache-2.0 +import io +import os +import argparse +import json +import shutil +import math +import sys +import time +import numpy as np +import importlib +import subprocess +import urllib.request + +from PIL import Image +from datetime import datetime +from dataclasses import dataclass +from typing import List +from pathlib import Path +from packaging import version + +sys.dont_write_bytecode = True + +GREEN = '\033[1;32m' +RED = '\033[1;31m' +RESET = '\033[0m' + +@dataclass +class AssetCopyConfig: + assets_path: str + target_path: str + spng_enable: bool + sjpg_enable: bool + qoi_enable: bool + sqoi_enable: bool + row_enable: bool + support_format: List[str] + split_height: int + +@dataclass +class PackModelsConfig: + target_path: str + include_path: str + image_file: str + assets_path: str + name_length: int + +def generate_header_filename(path): + asset_name = os.path.basename(path) + + header_filename = f'mmap_generate_{asset_name}.h' + return header_filename + +def compute_checksum(data): + checksum = sum(data) & 0xFFFF + return checksum + +def sort_key(filename): + basename, extension = os.path.splitext(filename) + return extension, basename + +def download_v8_script(convert_path): + """ + Ensure that the lvgl_image_converter repository is present at the specified path. + If not, clone the repository. Then, checkout to a specific commit. + + Parameters: + - convert_path (str): The directory path where lvgl_image_converter should be located. + """ + + # Check if convert_path is not empty + if convert_path: + # If the directory does not exist, create it and clone the repository + if not os.path.exists(convert_path): + os.makedirs(convert_path, exist_ok=True) + try: + subprocess.run( + ['git', 'clone', 'https://github.com/W-Mai/lvgl_image_converter.git', convert_path], + stdout=subprocess.DEVNULL, + stderr=subprocess.DEVNULL, + check=True + ) + except subprocess.CalledProcessError as e: + print(f'Git clone failed: {e}') + sys.exit(1) + + # Checkout to the specific commit + try: + subprocess.run( + ['git', 'checkout', '9174634e9dcc1b21a63668969406897aad650f35'], + cwd=convert_path, + stdout=subprocess.DEVNULL, + stderr=subprocess.DEVNULL, + check=True + ) + except subprocess.CalledProcessError as e: + print(f'Failed to checkout to the specific commit: {e}') + sys.exit(1) + else: + print('Error: convert_path is NULL') + sys.exit(1) + +def download_v9_script(url: str, destination: str) -> None: + """ + Download a Python script from a URL to a local destination. + + Parameters: + - url (str): URL to download the script from. + - destination (str): Local path to save the downloaded script. + + Raises: + - Exception: If the download fails. + """ + file_path = Path(destination) + + # Check if the file already exists + if file_path.exists(): + if file_path.is_file(): + return + + try: + # Create the parent directories if they do not exist + file_path.parent.mkdir(parents=True, exist_ok=True) + + # Open the URL and retrieve the data + with urllib.request.urlopen(url) as response, open(file_path, 'wb') as out_file: + data = response.read() # Read the entire response + out_file.write(data) # Write data to the local file + + except urllib.error.HTTPError as e: + print(f'HTTP Error: {e.code} - {e.reason} when accessing {url}') + sys.exit(1) + except urllib.error.URLError as e: + print(f'URL Error: {e.reason} when accessing {url}') + sys.exit(1) + except Exception as e: + print(f'An unexpected error occurred: {e}') + sys.exit(1) + +def split_image(im, block_size, input_dir, ext, convert_to_qoi): + """Splits the image into blocks based on the block size.""" + width, height = im.size + + if block_size: + splits = math.ceil(height / block_size) + else: + splits = 1 + + for i in range(splits): + if i < splits - 1: + crop = im.crop((0, i * block_size, width, (i + 1) * block_size)) + else: + crop = im.crop((0, i * block_size, width, height)) + + output_path = os.path.join(input_dir, str(i) + ext) + crop.save(output_path, quality=100) + + qoi_module = importlib.import_module('qoi-conv.qoi') + Qoi = qoi_module.Qoi + replace_extension = qoi_module.replace_extension + + if convert_to_qoi: + with Image.open(output_path) as img: + if img.mode != 'RGBA': + img = img.convert('RGBA') + + img_data = np.asarray(img) + out_path = qoi_module.replace_extension(output_path, 'qoi') + new_image = qoi_module.Qoi().save(out_path, img_data) + os.remove(output_path) + + + return width, height, splits + +def create_header(width, height, splits, split_height, lenbuf, ext): + """Creates the header for the output file based on the format.""" + header = bytearray() + + if ext.lower() == '.jpg': + header += bytearray('_SJPG__'.encode('UTF-8')) + elif ext.lower() == '.png': + header += bytearray('_SPNG__'.encode('UTF-8')) + elif ext.lower() == '.qoi': + header += bytearray('_SQOI__'.encode('UTF-8')) + + # 6 BYTES VERSION + header += bytearray(('\x00V1.00\x00').encode('UTF-8')) + + # WIDTH 2 BYTES + header += width.to_bytes(2, byteorder='little') + + # HEIGHT 2 BYTES + header += height.to_bytes(2, byteorder='little') + + # NUMBER OF ITEMS 2 BYTES + header += splits.to_bytes(2, byteorder='little') + + # SPLIT HEIGHT 2 BYTES + header += split_height.to_bytes(2, byteorder='little') + + for item_len in lenbuf: + # LENGTH 2 BYTES + header += item_len.to_bytes(2, byteorder='little') + + return header + +def save_image(output_file_path, header, split_data): + """Saves the image with the constructed header and split data.""" + with open(output_file_path, 'wb') as f: + if header is not None: + f.write(header + split_data) + else: + f.write(split_data) + +def handle_lvgl_version_v9(input_file: str, input_dir: str, + input_filename: str, convert_path: str) -> None: + """ + Handle conversion for LVGL versions greater than 9.0. + + Parameters: + - input_file (str): Path to the input image file. + - input_dir (str): Directory of the input file. + - input_filename (str): Name of the input file. + - convert_path (str): Path for conversion scripts and outputs. + """ + + convert_file = os.path.join(convert_path, 'LVGLImage.py') + lvgl_image_url = 'https://raw.githubusercontent.com/lvgl/lvgl/master/scripts/LVGLImage.py' + + download_v9_script(url=lvgl_image_url, destination=convert_file) + lvgl_script = Path(convert_file) + + cmd = [ + 'python', + str(lvgl_script), + '--ofmt', 'BIN', + '--cf', config_data['support_raw_cf'], + '--compress', 'NONE', + '--output', str(input_dir), + input_file + ] + + try: + result = subprocess.run( + cmd, + check=True, + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True + ) + print(f'Completed {input_filename} -> BIN') + except subprocess.CalledProcessError as e: + print('An error occurred while executing LVGLImage.py:') + print(e.stderr) + sys.exit(e.returncode) + +def handle_lvgl_version_v8(input_file: str, input_dir: str, input_filename: str, convert_path: str) -> None: + """ + Handle conversion for supported LVGL versions (<= 9.0). + + Parameters: + - input_file (str): Path to the input image file. + - input_dir (str): Directory of the input file. + - input_filename (str): Name of the input file. + - convert_path (str): Path for conversion scripts and outputs. + """ + + download_v8_script(convert_path=convert_path) + + if convert_path not in sys.path: + sys.path.append(convert_path) + + try: + import lv_img_conv + except ImportError as e: + print(f"Failed to import 'lv_img_conv' from '{convert_path}': {e}") + sys.exit(1) + + try: + lv_img_conv.conv_one_file( + root=Path(input_dir), + filepath=Path(input_file), + f=config_data['support_raw_ff'], + cf=config_data['support_raw_cf'], + ff='BIN', + dither=config_data['support_raw_dither'], + bgr_mode=config_data['support_raw_bgr'], + ) + print(f'Completed {input_filename} -> BIN') + except KeyError as e: + print(f'Missing configuration key: {e}') + sys.exit(1) + except Exception as e: + print(f'An error occurred during conversion: {e}') + sys.exit(1) + +def process_image(input_file, height_str, output_extension, convert_to_qoi=False): + """Main function to process the image and save it as .sjpg, .spng, or .sqoi.""" + try: + SPLIT_HEIGHT = int(height_str) + if SPLIT_HEIGHT < 0: + raise ValueError('Height must be a positive integer') + except ValueError as e: + print('Error: Height must be a positive integer') + sys.exit(1) + + input_dir, input_filename = os.path.split(input_file) + base_filename, ext = os.path.splitext(input_filename) + OUTPUT_FILE_NAME = base_filename + + try: + im = Image.open(input_file) + except Exception as e: + print('Error:', e) + sys.exit(0) + + width, height, splits = split_image(im, SPLIT_HEIGHT, input_dir, ext, convert_to_qoi) + + split_data = bytearray() + lenbuf = [] + + if convert_to_qoi: + ext = '.qoi' + + for i in range(splits): + with open(os.path.join(input_dir, str(i) + ext), 'rb') as f: + a = f.read() + split_data += a + lenbuf.append(len(a)) + os.remove(os.path.join(input_dir, str(i) + ext)) + + header = None + if splits == 1 and convert_to_qoi: + output_file_path = os.path.join(input_dir, OUTPUT_FILE_NAME + ext) + else: + header = create_header(width, height, splits, SPLIT_HEIGHT, lenbuf, ext) + output_file_path = os.path.join(input_dir, OUTPUT_FILE_NAME + output_extension) + + save_image(output_file_path, header, split_data) + + print('Completed', input_filename, '->', os.path.basename(output_file_path)) + +def convert_image_to_qoi(input_file, height_str): + process_image(input_file, height_str, '.sqoi', convert_to_qoi=True) + +def convert_image_to_simg(input_file, height_str): + input_dir, input_filename = os.path.split(input_file) + _, ext = os.path.splitext(input_filename) + output_extension = '.sjpg' if ext.lower() == '.jpg' else '.spng' + process_image(input_file, height_str, output_extension, convert_to_qoi=False) + +def convert_image_to_raw(input_file: str) -> None: + """ + Convert an image to raw binary format compatible with LVGL. + + Parameters: + - input_file (str): Path to the input image file. + + Raises: + - FileNotFoundError: If required scripts are not found. + - subprocess.CalledProcessError: If the external conversion script fails. + - KeyError: If required keys are missing in config_data. + """ + input_dir, input_filename = os.path.split(input_file) + _, ext = os.path.splitext(input_filename) + convert_path = os.path.join(os.path.dirname(input_file), 'lvgl_image_converter') + lvgl_ver_str = config_data.get('lvgl_ver', '9.0.0') + + try: + lvgl_version = version.parse(lvgl_ver_str) + except version.InvalidVersion: + print(f'Invalid LVGL version format: {lvgl_ver_str}') + sys.exit(1) + + if lvgl_version >= version.parse('9.0.0'): + handle_lvgl_version_v9( + input_file=input_file, + input_dir=input_dir, + input_filename=input_filename, + convert_path=convert_path + ) + else: + handle_lvgl_version_v8( + input_file=input_file, + input_dir=input_dir, + input_filename=input_filename, + convert_path=convert_path + ) + +def pack_assets(config: PackModelsConfig): + """ + Pack models based on the provided configuration. + """ + + target_path = config.target_path + assets_include_path = config.include_path + out_file = config.image_file + assets_path = config.assets_path + max_name_len = config.name_length + + merged_data = bytearray() + file_info_list = [] + skip_files = ['config.json', 'lvgl_image_converter'] + + file_list = sorted(os.listdir(target_path), key=sort_key) + for filename in file_list: + if filename in skip_files: + continue + + file_path = os.path.join(target_path, filename) + file_name = os.path.basename(file_path) + file_size = os.path.getsize(file_path) + + try: + img = Image.open(file_path) + width, height = img.size + except Exception as e: + # print("Error:", e) + _, file_extension = os.path.splitext(file_path) + if file_extension.lower() in ['.sjpg', '.spng', '.sqoi']: + offset = 14 + with open(file_path, 'rb') as f: + f.seek(offset) + width_bytes = f.read(2) + height_bytes = f.read(2) + width = int.from_bytes(width_bytes, byteorder='little') + height = int.from_bytes(height_bytes, byteorder='little') + else: + width, height = 0, 0 + + file_info_list.append((file_name, len(merged_data), file_size, width, height)) + # Add 0x5A5A prefix to merged_data + merged_data.extend(b'\x5A' * 2) + + with open(file_path, 'rb') as bin_file: + bin_data = bin_file.read() + + merged_data.extend(bin_data) + + total_files = len(file_info_list) + + mmap_table = bytearray() + for file_name, offset, file_size, width, height in file_info_list: + if len(file_name) > int(max_name_len): + print(f'\033[1;33mWarn:\033[0m "{file_name}" exceeds {max_name_len} bytes and will be truncated.') + fixed_name = file_name.ljust(int(max_name_len), '\0')[:int(max_name_len)] + mmap_table.extend(fixed_name.encode('utf-8')) + mmap_table.extend(file_size.to_bytes(4, byteorder='little')) + mmap_table.extend(offset.to_bytes(4, byteorder='little')) + mmap_table.extend(width.to_bytes(2, byteorder='little')) + mmap_table.extend(height.to_bytes(2, byteorder='little')) + + combined_data = mmap_table + merged_data + combined_checksum = compute_checksum(combined_data) + combined_data_length = len(combined_data).to_bytes(4, byteorder='little') + header_data = total_files.to_bytes(4, byteorder='little') + combined_checksum.to_bytes(4, byteorder='little') + final_data = header_data + combined_data_length + combined_data + + with open(out_file, 'wb') as output_bin: + output_bin.write(final_data) + + os.makedirs(assets_include_path, exist_ok=True) + current_year = datetime.now().year + + asset_name = os.path.basename(assets_path) + file_path = os.path.join(assets_include_path, f'mmap_generate_{asset_name}.h') + with open(file_path, 'w') as output_header: + output_header.write('/*\n') + output_header.write(' * SPDX-FileCopyrightText: 2022-{} Espressif Systems (Shanghai) CO LTD\n'.format(current_year)) + output_header.write(' *\n') + output_header.write(' * SPDX-License-Identifier: Apache-2.0\n') + output_header.write(' */\n\n') + output_header.write('/**\n') + output_header.write(' * @file\n') + output_header.write(" * @brief This file was generated by esp_mmap_assets, don't modify it\n") + output_header.write(' */\n\n') + output_header.write('#pragma once\n\n') + output_header.write("#include \"esp_mmap_assets.h\"\n\n") + output_header.write(f'#define MMAP_{asset_name.upper()}_FILES {total_files}\n') + output_header.write(f'#define MMAP_{asset_name.upper()}_CHECKSUM 0x{combined_checksum:04X}\n\n') + output_header.write(f'enum MMAP_{asset_name.upper()}_LISTS {{\n') + + for i, (file_name, _, _, _, _) in enumerate(file_info_list): + enum_name = file_name.replace('.', '_') + output_header.write(f' MMAP_{asset_name.upper()}_{enum_name.upper()} = {i}, /*!< {file_name} */\n') + + output_header.write('};\n') + + print(f'All bin files have been merged into {os.path.basename(out_file)}') + +def copy_assets(config: AssetCopyConfig): + """ + Copy assets to target_path based on the provided configuration. + """ + format_tuple = tuple(config.support_format) + assets_path = config.assets_path + target_path = config.target_path + + for filename in os.listdir(assets_path): + if any(filename.endswith(suffix) for suffix in format_tuple): + source_file = os.path.join(assets_path, filename) + target_file = os.path.join(target_path, filename) + shutil.copyfile(source_file, target_file) + + conversion_map = { + '.jpg': [ + (config.sjpg_enable, convert_image_to_simg), + (config.qoi_enable, convert_image_to_qoi), + ], + '.png': [ + (config.spng_enable, convert_image_to_simg), + (config.qoi_enable, convert_image_to_qoi), + ], + } + + file_ext = os.path.splitext(filename)[1].lower() + conversions = conversion_map.get(file_ext, []) + converted = False + + for enable_flag, convert_func in conversions: + if enable_flag: + convert_func(target_file, config.split_height) + os.remove(target_file) + converted = True + break + + if not converted and config.row_enable: + convert_image_to_raw(target_file) + os.remove(target_file) + else: + print(f'No match found for file: {filename}, format_tuple: {format_tuple}') + +def process_assets_build(config_data): + assets_path = config_data['assets_path'] + image_file = config_data['image_file'] + target_path = os.path.dirname(image_file) + include_path = config_data['include_path'] + name_length = config_data['name_length'] + split_height = config_data['split_height'] + support_format = [fmt.strip() for fmt in config_data['support_format'].split(',')] + + copy_config = AssetCopyConfig( + assets_path=assets_path, + target_path=target_path, + spng_enable=config_data['support_spng'], + sjpg_enable=config_data['support_sjpg'], + qoi_enable=config_data['support_qoi'], + sqoi_enable=config_data['support_sqoi'], + row_enable=config_data['support_raw'], + support_format=support_format, + split_height=split_height + ) + + pack_config = PackModelsConfig( + target_path=target_path, + include_path=include_path, + image_file=image_file, + assets_path=assets_path, + name_length=name_length + ) + + print('--support_format:', support_format) + + if '.jpg' in support_format or '.png' in support_format: + print('--support_spng:', copy_config.spng_enable) + print('--support_sjpg:', copy_config.sjpg_enable) + print('--support_qoi:', copy_config.qoi_enable) + print('--support_raw:', copy_config.row_enable) + + if copy_config.sqoi_enable: + print('--support_sqoi:', copy_config.sqoi_enable) + if copy_config.spng_enable or copy_config.sjpg_enable or copy_config.sqoi_enable: + print('--split_height:', copy_config.split_height) + if copy_config.row_enable: + print('--lvgl_version:', config_data['lvgl_ver']) + + if not os.path.exists(target_path): + os.makedirs(target_path, exist_ok=True) + for filename in os.listdir(target_path): + file_path = os.path.join(target_path, filename) + if os.path.isfile(file_path) or os.path.islink(file_path): + os.unlink(file_path) + elif os.path.isdir(file_path): + shutil.rmtree(file_path) + + copy_assets(copy_config) + pack_assets(pack_config) + + total_size = os.path.getsize(os.path.join(target_path, image_file)) + recommended_size = math.ceil(total_size / 1024) + partition_size = math.ceil(int(config_data['assets_size'], 16)) + + print(f'{"Total size:":<30} {GREEN}{total_size / 1024:>8.2f}K ({total_size}){RESET}') + print(f'{"Partition size:":<30} {GREEN}{partition_size / 1024:>8.2f}K ({partition_size}){RESET}') + + if int(config_data['assets_size'], 16) <= total_size: + print(f'Recommended partition size: {GREEN}{recommended_size}K{RESET}') + print(f'{RED}Error:Binary size exceeds partition size.{RESET}') + sys.exit(1) + +def process_assets_merge(config_data): + app_bin_path = config_data['app_bin_path'] + image_file = config_data['image_file'] + target_path = os.path.dirname(image_file) + + combined_bin_path = os.path.join(target_path, 'combined.bin') + append_bin_path = os.path.join(target_path, image_file) + + app_size = os.path.getsize(app_bin_path) + asset_size = os.path.getsize(append_bin_path) + total_size = asset_size + app_size + recommended_size = math.ceil(total_size / 1024) + partition_size = math.ceil(int(config_data['assets_size'], 16)) + + print(f'{"Asset size:":<30} {GREEN}{asset_size / 1024:>8.2f}K ({asset_size}){RESET}') + print(f'{"App size:":<30} {GREEN}{app_size / 1024:>8.2f}K ({app_size}){RESET}') + print(f'{"Total size:":<30} {GREEN}{total_size / 1024:>8.2f}K ({total_size}){RESET}') + print(f'{"Partition size:":<30} {GREEN}{partition_size / 1024:>8.2f}K ({partition_size}){RESET}') + + if total_size > partition_size: + print(f'Recommended partition size: {GREEN}{recommended_size}K{RESET}') + print(f'{RED}Error:Binary size exceeds partition size.{RESET}') + sys.exit(1) + + with open(combined_bin_path, 'wb') as combined_bin: + with open(app_bin_path, 'rb') as app_bin: + combined_bin.write(app_bin.read()) + with open(append_bin_path, 'rb') as img_bin: + combined_bin.write(img_bin.read()) + + shutil.move(combined_bin_path, app_bin_path) + print(f'Append bin created: {os.path.basename(app_bin_path)}') + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Move and Pack assets.') + parser.add_argument('--config', required=True, help='Path to the configuration file') + parser.add_argument('--merge', action='store_true', help='Merge assets with app binary') + args = parser.parse_args() + + with open(args.config, 'r') as f: + config_data = json.load(f) + + if args.merge: + process_assets_merge(config_data) + else: + process_assets_build(config_data) diff --git a/scripts/versions.py b/scripts/versions.py new file mode 100644 index 0000000..ac9472c --- /dev/null +++ b/scripts/versions.py @@ -0,0 +1,250 @@ +#! /usr/bin/env python3 +from dotenv import load_dotenv +load_dotenv() + +import os +import struct +import zipfile +import oss2 +import json +import requests +from requests.exceptions import RequestException + +# 切换到项目根目录 +os.chdir(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) + +def get_chip_id_string(chip_id): + return { + 0x0000: "esp32", + 0x0002: "esp32s2", + 0x0005: "esp32c3", + 0x0009: "esp32s3", + 0x000C: "esp32c2", + 0x000D: "esp32c6", + 0x0010: "esp32h2", + 0x0011: "esp32c5", + 0x0012: "esp32p4", + 0x0017: "esp32c5", + }[chip_id] + +def get_flash_size(flash_size): + MB = 1024 * 1024 + return { + 0x00: 1 * MB, + 0x01: 2 * MB, + 0x02: 4 * MB, + 0x03: 8 * MB, + 0x04: 16 * MB, + 0x05: 32 * MB, + 0x06: 64 * MB, + 0x07: 128 * MB, + }[flash_size] + +def get_app_desc(data): + magic = struct.unpack("> 4) + chip_id = get_chip_id_string(app_data[0xC]) + # get segments + segment_count = app_data[0x1] + segments = [] + offset = 0x18 + image_size = 0x18 + for i in range(segment_count): + segment_size = struct.unpack("