17 Commits

Author SHA1 Message Date
Rune Harlyk 6108aa9bf6 Switch to UV 2026-05-11 21:01:45 +02:00
Rune Harlyk b590f157e1 🔥 Removes unused sim test script 2026-05-11 21:01:14 +02:00
Rune Harlyk 0f2a0c65ba 🐛 Use mpu.heading for heading calculations 2026-03-20 17:19:41 +01:00
Rune Harlyk 37474e840d Update clone command to include submodules 2026-03-20 16:06:39 +01:00
Rune Harlyk e1d37a907d 🐛 ESP P4 i2c pull up 2026-03-06 23:35:20 +01:00
Rune Harlyk eba00f98cd Clean up macros 2026-02-09 16:39:46 +01:00
Rune Harlyk 43e7f13888 Adds working camera stream for p4 with correct colors and good perf 2026-02-09 16:39:46 +01:00
Rune Harlyk d81b1b0851 🙏 Working camera stream with p4 2026-02-09 16:39:46 +01:00
Rune Harlyk bf2fd957af Adds support for esp32 P4 2026-02-09 16:39:46 +01:00
Rune Harlyk d6075deb6c 🔥 Removes old stateful persistence 2026-02-01 00:45:55 +01:00
Rune Harlyk ff1444b2bc Makes wifi try to connect to latest 2026-01-31 21:05:37 +01:00
Rune Harlyk e5e9841dd3 Sets cpu freq to 240 2026-01-31 21:00:39 +01:00
Rune Harlyk f4f8035f37 🐛 Handle spa 2026-01-31 19:32:43 +01:00
Rune Harlyk 13300aa9e0 🎨 Update monitor filters 2026-01-31 19:32:43 +01:00
Rune Harlyk cdf6c83be5 ♻️ Moves sdkconfig.defaults 2026-01-31 19:32:43 +01:00
Rune Harlyk bd984309f1 ♻️ Handle merging 2026-01-31 19:32:43 +01:00
Rune Harlyk aca8ee6de5 Full migration to esp-idf 2026-01-31 19:32:43 +01:00
70 changed files with 4489 additions and 1151 deletions
+5
View File
@@ -6,6 +6,11 @@ __pycache__/
*.py[cod]
*$py.class
.pio
managed_components/
dependencies.lock
sdkconfig
sdkconfig.*
!sdkconfig.defaults
esp32/src/platform_shared/*
!esp32/src/platform_shared/.gitkeep
app/src/lib/platform_shared/*
+1 -1
View File
@@ -13,7 +13,7 @@
},
"editor.tabSize": 4,
"editor.detectIndentation": false,
"cmake.sourceDirectory": "C:/data/repos/Hardware/Spot Micro - Leika/.pio/libdeps/esp32cam/esp32-camera",
"cmake.sourceDirectory": "C:/data/repos/Hardware/Spot_Micro_Leika",
"cSpell.words": [
"Adafruit",
"IRAM",
+3
View File
@@ -0,0 +1,3 @@
cmake_minimum_required(VERSION 3.16.0)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(Spot_Micro_Leika)
+3 -2
View File
@@ -262,8 +262,9 @@
const rotatedXm = settings.xm * cosTotal - settings.zm * sinTotal
const rotatedZm = settings.xm * sinTotal + settings.zm * cosTotal
const cosHead = Math.cos(headingYaw)
const sinHead = Math.sin(headingYaw)
const mpuHeadingRad = degToRad($mpu.heading)
const cosHead = Math.cos(mpuHeadingRad)
const sinHead = Math.sin(mpuHeadingRad)
const rotatedCumX = body_state.cumulative_x * cosHead - body_state.cumulative_z * sinHead
const rotatedCumZ = body_state.cumulative_x * sinHead + body_state.cumulative_z * cosHead
@@ -245,10 +245,6 @@
angleChart.update('none')
}
if ($features.mag) {
updateChartData(magnetometerChart, $imu.heading)
}
if ($features.bmp && tempChart && altitudeChart) {
updateChartData(
tempChart,
+33
View File
@@ -0,0 +1,33 @@
{
"build": {
"core": "esp32",
"extra_flags": [
"-DBOARD_HAS_PSRAM"
],
"f_cpu": "360000000L",
"f_flash": "80000000L",
"f_psram": "200000000L",
"flash_mode": "qio",
"mcu": "esp32p4",
"variant": "esp32p4"
},
"connectivity": [
"wifi"
],
"debug": {
"openocd_target": "esp32p4.cfg"
},
"frameworks": [
"espidf"
],
"name": "ESP32-P4 Dev Board (32MB PSRAM + 32MB Flash, C6 coprocessor)",
"upload": {
"flash_size": "32MB",
"maximum_ram_size": 786432,
"maximum_size": 33554432,
"require_upload_port": true,
"speed": 1500000
},
"url": "https://docs.espressif.com/projects/esp-dev-kits/en/latest/esp32p4/",
"vendor": "Espressif"
}
-2
View File
@@ -13,8 +13,6 @@ build_flags =
-D USE_HMC5883=0
-D USE_BMP180=0
-D USE_MPU6050=0
-D USE_ICM20948=1
-D USE_ICM20948_SPIMODE=0
-D USE_WS2812=1
-D USE_BNO055=0
-D USE_USS=0
+7 -5
View File
@@ -2,11 +2,13 @@
#include <template/stateful_service.h>
#include <template/stateful_proto_endpoint.h>
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <settings/ap_settings.h>
#include <utils/timing.h>
#include <WiFi.h>
#include "esp_timer.h"
#include <wifi/wifi_idf.h>
#include <wifi/dns_server.h>
#include <esp_timer.h>
#include <string>
class APService : public StatefulService<APSettings> {
public:
@@ -28,8 +30,8 @@ class APService : public StatefulService<APSettings> {
DNSServer *_dnsServer;
volatile unsigned long _lastManaged;
volatile boolean _reconfigureAp;
volatile boolean _recoveryMode = false;
volatile bool _reconfigureAp;
volatile bool _recoveryMode = false;
void reconfigureAP();
void manageAP();
@@ -1,5 +1,8 @@
#pragma once
#include <esp_log.h>
#include <freertos/FreeRTOS.h>
#include <freertos/semphr.h>
#include <functional>
#include <list>
#include <map>
+7
View File
@@ -1,6 +1,13 @@
#pragma once
#ifndef CONFIG_HTTPD_WS_SUPPORT
#define CONFIG_HTTPD_WS_SUPPORT 1
#endif
#include <esp_http_server.h>
#include <esp_log.h>
#include <freertos/FreeRTOS.h>
#include <freertos/semphr.h>
#include <functional>
#include <vector>
#include <string>
+1 -1
View File
@@ -1,6 +1,6 @@
#pragma once
#include <Arduino.h>
#include <cstdint>
#include <communication/webserver.h>
#include <communication/comm_base.hpp>
+21
View File
@@ -0,0 +1,21 @@
#pragma once
#ifndef PROGMEM
#define PROGMEM
#endif
#ifndef PGM_P
#define PGM_P const char *
#endif
#ifndef pgm_read_byte
#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
#endif
#ifndef pgm_read_word
#define pgm_read_word(addr) (*(const unsigned short *)(addr))
#endif
#ifndef pgm_read_dword
#define pgm_read_dword(addr) (*(const unsigned long *)(addr))
#endif
+2 -11
View File
@@ -1,7 +1,7 @@
#pragma once
#include <WiFi.h>
#include <ArduinoJson.h>
#include <sdkconfig.h>
#include <wifi/wifi_idf.h>
#include <esp_http_server.h>
#include "platform_shared/message.pb.h"
@@ -19,15 +19,6 @@
#define USE_BNO055 1
#endif
// ESP32 IMU off by default
#ifndef USE_ICM20948
#define USE_ICM20948 0
#endif
#ifndef USE_ICM20948_SPIMODE // I2C on by default
#define USE_ICM20948_SPIMODE 0
#endif
// ESP32 magnetometer on by default
#ifndef USE_HMC5883
#define USE_HMC5883 0
#endif
+22 -12
View File
@@ -1,29 +1,39 @@
#pragma once
#include <esp_http_server.h>
#include <ArduinoJson.h>
#include <LittleFS.h>
#include <esp_littlefs.h>
#include <esp_vfs.h>
#include <dirent.h>
#include <sys/stat.h>
#include <string>
#include <cstdio>
#include <platform_shared/api.pb.h>
#define ESP_FS LittleFS
#define FS_CONFIG_DIRECTORY "/config"
#define DEVICE_CONFIG_FILE "/config/peripheral.json"
#define CAMERA_SETTINGS_FILE "/config/cameraSettings.pb"
#define AP_SETTINGS_FILE "/config/apSettings.pb"
#define MDNS_SETTINGS_FILE "/config/mdnsSettings.pb"
#define WIFI_SETTINGS_FILE "/config/wifiSettings.pb"
#define PERIPHERAL_SETTINGS_FILE "/config/peripheralSettings.pb"
#define SERVO_SETTINGS_FILE "/config/servoSettings.pb"
#define MOUNT_POINT "/littlefs"
#define FS_CONFIG_DIRECTORY MOUNT_POINT "/config"
#define DEVICE_CONFIG_FILE MOUNT_POINT "/config/peripheral.pb"
#define CAMERA_SETTINGS_FILE MOUNT_POINT "/config/cameraSettings.pb"
#define AP_SETTINGS_FILE MOUNT_POINT "/config/apSettings.pb"
#define MDNS_SETTINGS_FILE MOUNT_POINT "/config/mdnsSettings.pb"
#define WIFI_SETTINGS_FILE MOUNT_POINT "/config/wifiSettings.pb"
#define PERIPHERAL_SETTINGS_FILE MOUNT_POINT "/config/peripheralSettings.pb"
#define SERVO_SETTINGS_FILE MOUNT_POINT "/config/servoSettings.pb"
namespace FileSystem {
bool init();
void listFilesProto(const std::string &directory, api_FileEntry *entry);
std::string listFiles(const std::string &directory, bool isRoot = true);
bool deleteFile(const char *filename);
bool editFile(const char *filename, const uint8_t *content, size_t size);
bool editFile(const char *filename, const char *content);
bool fileExists(const char *filename);
std::string readFile(const char *filename);
bool writeFile(const char *filename, const char *content);
bool writeFile(const char *filename, const uint8_t *content, size_t size);
bool mkdirRecursive(const char *path);
esp_err_t getFilesProto(httpd_req_t *request);
esp_err_t getFiles(httpd_req_t *request);
+6 -27
View File
@@ -1,20 +1,20 @@
#pragma once
#include <LittleFS.h>
#include <platform_shared/message.pb.h>
#include <filesystem.h>
#include <map>
#include <string>
#include <functional>
#include <cstdio>
// Make sure that this aligns with socket_message.FSDownloadData.data max_size (and for upload)
#define FS_MAX_CHUNK_SIZE 16384 // ~= 16 kb
#define FS_TRANSFER_TIMEOUT_MS 30000 // 30 seconds
#define FS_MAX_CHUNK_SIZE 16384
#define FS_TRANSFER_TIMEOUT_MS 30000
namespace FileSystemWS {
struct DownloadState {
std::string path;
File file;
FILE* file;
uint32_t fileSize;
uint32_t chunkSize;
uint32_t totalChunks;
@@ -25,7 +25,7 @@ struct DownloadState {
struct UploadState {
std::string path;
File file;
FILE* file;
uint32_t fileSize;
uint32_t totalChunks;
uint32_t chunksReceived;
@@ -36,7 +36,6 @@ struct UploadState {
std::string errorMessage;
};
// Callback type for sending messages to clients
using SendMetadataCallback = std::function<void(const socket_message_FSDownloadMetadata&, int clientId)>;
using SendCallback = std::function<void(const socket_message_FSDownloadData&, int clientId)>;
using SendCompleteCallback = std::function<void(const socket_message_FSDownloadComplete&, int clientId)>;
@@ -46,35 +45,17 @@ class FileSystemHandler {
public:
FileSystemHandler();
// Set callbacks for sending streaming data
void setSendCallbacks(SendMetadataCallback sendMetadata, SendCallback sendData, SendCompleteCallback sendComplete,
SendUploadCompleteCallback sendUploadComplete);
// Delete file/directory
socket_message_FSDeleteResponse handleDelete(const socket_message_FSDeleteRequest& req);
// Create directory
socket_message_FSMkdirResponse handleMkdir(const socket_message_FSMkdirRequest& req);
// List directory
socket_message_FSListResponse handleList(const socket_message_FSListRequest& req);
// Streaming download - starts the download and streams all chunks
void handleDownloadRequest(const socket_message_FSDownloadRequest& req, int clientId);
// Streaming upload - start upload session
socket_message_FSUploadStartResponse handleUploadStart(const socket_message_FSUploadStart& req, int clientId);
// Streaming upload - receive chunk data (fire-and-forget from client)
void handleUploadData(const socket_message_FSUploadData& req);
// Cancel transfer
socket_message_FSCancelTransferResponse handleCancelTransfer(const socket_message_FSCancelTransfer& req);
// Cleanup expired transfers
void cleanupExpiredTransfers();
// Process pending downloads (call from main loop)
void processPendingDownloads();
private:
@@ -91,9 +72,7 @@ class FileSystemHandler {
void listDirectory(const std::string& path, socket_message_FSListResponse& response);
bool deleteRecursive(const std::string& path);
bool sendNextDownloadChunk(uint32_t transferId);
void finalizeUpload(uint32_t transferId, bool success, const std::string& error = "");
};
+28 -16
View File
@@ -1,14 +1,15 @@
#pragma once
#include <esp32-hal.h>
#include <sdkconfig.h>
#include <esp_system.h>
#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
#if CONFIG_IDF_TARGET_ESP32
#include "esp32/rom/rtc.h"
#ifndef ESP_PLATFORM_NAME
#define ESP_PLATFORM_NAME "ESP32"
#endif
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32/rom/rtc.h"
#include "esp32s2/rom/rtc.h"
#ifndef ESP_PLATFORM_NAME
#define ESP_PLATFORM_NAME "ESP32-S2"
#endif
@@ -22,28 +23,39 @@
#ifndef ESP_PLATFORM_NAME
#define ESP_PLATFORM_NAME "ESP32-S3"
#endif
#elif CONFIG_IDF_TARGET_ESP32C6
#include "esp32c6/rom/rtc.h"
#ifndef ESP_PLATFORM_NAME
#define ESP_PLATFORM_NAME "ESP32-C6"
#endif
#elif CONFIG_IDF_TARGET_ESP32P4
#include "esp32p4/rom/rtc.h"
#ifndef ESP_PLATFORM_NAME
#define ESP_PLATFORM_NAME "ESP32-P4"
#endif
#define ESP32P4_USES_C6_COPROCESSOR 1
#else
#error Target CONFIG_IDF_TARGET is not supported
#endif
#ifndef ARDUINO_VERSION
#ifndef STRINGIFY
#define STRINGIFY(s) #s
#endif
#define ARDUINO_VERSION_STR(major, minor, patch) "v" STRINGIFY(major) "." STRINGIFY(minor) "." STRINGIFY(patch)
#define ARDUINO_VERSION \
ARDUINO_VERSION_STR(ESP_ARDUINO_VERSION_MAJOR, ESP_ARDUINO_VERSION_MINOR, ESP_ARDUINO_VERSION_PATCH)
#endif
/*
* I2C software connection
*/
#if CONFIG_IDF_TARGET_ESP32P4
#ifndef SDA_PIN
#define SDA_PIN SDA
#define SDA_PIN 7
#endif
#ifndef SCL_PIN
#define SCL_PIN SCL
#define SCL_PIN 8
#endif
#else
#ifndef SDA_PIN
#define SDA_PIN 21
#endif
#ifndef SCL_PIN
#define SCL_PIN 22
#endif
#endif
#ifndef I2C_FREQUENCY
#define I2C_FREQUENCY 100000UL
#endif
#define I2C_FREQUENCY 1000000UL
#endif
+11 -11
View File
@@ -1,23 +1,14 @@
#pragma once
#include <esp_http_server.h>
#include <ESPmDNS.h>
#include <mdns.h>
#include <template/stateful_service.h>
#include <template/stateful_proto_endpoint.h>
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <settings/mdns_settings.h>
#include <utils/timing.h>
class MDNSService : public StatefulService<MDNSSettings> {
private:
FSPersistencePB<MDNSSettings> _persistence;
bool _started {false};
void reconfigureMDNS();
void startMDNS();
void stopMDNS();
void addServices();
public:
MDNSService();
~MDNSService();
@@ -28,4 +19,13 @@ class MDNSService : public StatefulService<MDNSSettings> {
esp_err_t queryServices(httpd_req_t *request, api_Request *protoReq);
StatefulProtoEndpoint<MDNSSettings, api_MDNSSettings> protoEndpoint;
private:
FSPersistencePB<MDNSSettings> _persistence;
bool _started {false};
void reconfigureMDNS();
void startMDNS();
void stopMDNS();
void addServices();
};
+5 -3
View File
@@ -2,6 +2,8 @@
#include <kinematics.h>
#include <message_types.h>
#include <utils/math_utils.h>
#include <cstring>
class MotionState {
protected:
@@ -26,15 +28,15 @@ class MotionState {
}
void updateFeet(body_state_t& body_state, const float smoothing_factor = default_smoothing_factor) {
if (target_body_state.feet != body_state.feet) {
if (std::memcmp(target_body_state.feet, body_state.feet, sizeof(body_state.feet)) != 0) {
body_state.updateFeet(target_body_state.feet);
}
}
public:
void updateImuOffsets(const float new_omega, const float new_psi) {
omega_offset = new_omega * RAD_TO_DEG;
psi_offset = new_psi * RAD_TO_DEG;
omega_offset = RAD_TO_DEG_F(new_omega);
psi_offset = RAD_TO_DEG_F(new_psi);
}
virtual ~MotionState() {}
+1
View File
@@ -2,6 +2,7 @@
#include <motion_states/state.h>
#include <utils/math_utils.h>
#include <algorithm>
#include <array>
#include <functional>
+1 -1
View File
@@ -13,7 +13,7 @@ struct BarometerMsg {
class Barometer : public SensorBase<BarometerMsg> {
public:
bool initialize(void* _) {
bool initialize() override {
_msg.success = _bmp.begin();
if (_msg.success) {
ESP_LOGI("BMP", "BMP180 initialized successfully");
+15 -8
View File
@@ -1,30 +1,35 @@
#pragma once
#include <esp_http_server.h>
#include <WiFi.h>
#include <features.h>
#include <template/stateful_service.h>
#include <template/stateful_proto_endpoint.h>
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <settings/camera_settings.h>
namespace Camera {
#define USE_DVP_CAMERA (USE_CAMERA && !CONFIG_IDF_TARGET_ESP32P4)
#define USE_CSI_CAMERA (USE_CAMERA && CONFIG_IDF_TARGET_ESP32P4)
#if USE_DVP_CAMERA
#include <esp_camera.h>
#if USE_CAMERA
#include <peripherals/camera_pins.h>
#endif
#define PART_BOUNDARY "frame"
camera_fb_t *safe_camera_fb_get();
sensor_t *safe_sensor_get();
void safe_sensor_return();
#endif
class CameraService : public StatefulService<CameraSettings> {
#define PART_BOUNDARY "frame"
class CameraService
#if USE_DVP_CAMERA
: public StatefulService<CameraSettings>
#endif
{
public:
CameraService();
@@ -33,10 +38,12 @@ class CameraService : public StatefulService<CameraSettings> {
esp_err_t cameraStill(httpd_req_t *request);
esp_err_t cameraStream(httpd_req_t *request);
#if USE_DVP_CAMERA
StatefulProtoEndpoint<CameraSettings, api_CameraSettings> protoEndpoint;
private:
FSPersistencePB<CameraSettings> _persistence;
void updateCamera();
#endif
};
} // namespace Camera
+1 -2
View File
@@ -316,8 +316,7 @@ class MPU6050Driver {
i += chunkSize;
address += chunkSize;
if (address == 0 || address >= 256) {
address = 0;
if (address == 0) {
bank++;
setMemoryBank(bank);
}
+56 -67
View File
@@ -1,11 +1,12 @@
#pragma once
#include <driver/i2c.h>
#include <driver/i2c_master.h>
#include <esp_log.h>
#include <freertos/FreeRTOS.h>
#include <freertos/semphr.h>
#include <functional>
#include <vector>
#include <cstring>
class I2CBus {
public:
@@ -24,30 +25,21 @@ class I2CBus {
_scl = scl;
_freq = freq;
i2c_config_t conf = {};
conf.mode = I2C_MODE_MASTER;
conf.sda_io_num = sda;
conf.scl_io_num = scl;
conf.sda_pullup_en = GPIO_PULLUP_ENABLE;
conf.scl_pullup_en = GPIO_PULLUP_ENABLE;
conf.master.clk_speed = freq;
i2c_master_bus_config_t bus_cfg = {};
bus_cfg.i2c_port = port;
bus_cfg.sda_io_num = sda;
bus_cfg.scl_io_num = scl;
bus_cfg.clk_source = I2C_CLK_SRC_DEFAULT;
bus_cfg.glitch_ignore_cnt = 7;
#if CONFIG_IDF_TARGET_ESP32P4
bus_cfg.flags.enable_internal_pullup = false;
#else
bus_cfg.flags.enable_internal_pullup = true;
#endif
esp_err_t err = i2c_param_config(_port, &conf);
esp_err_t err = i2c_new_master_bus(&bus_cfg, &_bus);
if (err != ESP_OK) {
ESP_LOGE(TAG, "i2c_param_config failed: %s", esp_err_to_name(err));
return err;
}
err = i2c_driver_install(_port, I2C_MODE_MASTER, 0, 0, 0);
if (err == ESP_ERR_INVALID_STATE) {
ESP_LOGW(TAG, "I2C driver already installed for port %d, reconfiguring", _port);
i2c_driver_delete(_port);
err = i2c_param_config(_port, &conf);
if (err != ESP_OK) return err;
err = i2c_driver_install(_port, I2C_MODE_MASTER, 0, 0, 0);
}
if (err != ESP_OK) {
ESP_LOGE(TAG, "i2c_driver_install failed: %s", esp_err_to_name(err));
ESP_LOGE(TAG, "i2c_new_master_bus failed: %s", esp_err_to_name(err));
return err;
}
@@ -57,73 +49,51 @@ class I2CBus {
void end() {
if (_initialized) {
i2c_driver_delete(_port);
if (_dev) {
i2c_master_bus_rm_device(_dev);
_dev = NULL;
_dev_addr = 0xFF;
}
i2c_del_master_bus(_bus);
_bus = NULL;
_initialized = false;
}
}
bool isInitialized() const { return _initialized; }
i2c_master_bus_handle_t busHandle() const { return _bus; }
esp_err_t writeBytes(uint8_t addr, const uint8_t* data, size_t len) {
if (!_initialized) return ESP_ERR_INVALID_STATE;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, (addr << 1) | I2C_MASTER_WRITE, true);
if (len > 0 && data != nullptr) {
i2c_master_write(cmd, data, len, true);
}
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(_port, cmd, pdMS_TO_TICKS(100));
i2c_cmd_link_delete(cmd);
return ret;
esp_err_t err = ensureDevice(addr);
if (err != ESP_OK) return err;
return i2c_master_transmit(_dev, data, len, pdMS_TO_TICKS(200));
}
esp_err_t writeReg(uint8_t addr, uint8_t reg, const uint8_t* data, size_t len) {
if (!_initialized) return ESP_ERR_INVALID_STATE;
esp_err_t err = ensureDevice(addr);
if (err != ESP_OK) return err;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, (addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_write_byte(cmd, reg, true);
uint8_t buf[len + 1];
buf[0] = reg;
if (len > 0 && data != nullptr) {
i2c_master_write(cmd, data, len, true);
memcpy(buf + 1, data, len);
}
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(_port, cmd, pdMS_TO_TICKS(100));
i2c_cmd_link_delete(cmd);
return ret;
return i2c_master_transmit(_dev, buf, len + 1, pdMS_TO_TICKS(200));
}
esp_err_t readReg(uint8_t addr, uint8_t reg, uint8_t* data, size_t len) {
if (!_initialized) return ESP_ERR_INVALID_STATE;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, (addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_write_byte(cmd, reg, true);
i2c_master_start(cmd);
i2c_master_write_byte(cmd, (addr << 1) | I2C_MASTER_READ, true);
if (len > 1) {
i2c_master_read(cmd, data, len - 1, I2C_MASTER_ACK);
}
i2c_master_read_byte(cmd, data + len - 1, I2C_MASTER_NACK);
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(_port, cmd, pdMS_TO_TICKS(100));
i2c_cmd_link_delete(cmd);
return ret;
esp_err_t err = ensureDevice(addr);
if (err != ESP_OK) return err;
return i2c_master_transmit_receive(_dev, &reg, 1, data, len, pdMS_TO_TICKS(200));
}
bool probe(uint8_t addr) {
if (!_initialized) return false;
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, (addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(_port, cmd, pdMS_TO_TICKS(50));
i2c_cmd_link_delete(cmd);
return ret == ESP_OK;
return i2c_master_probe(_bus, addr, pdMS_TO_TICKS(200)) == ESP_OK;
}
std::vector<uint8_t> scan(uint8_t lower = 1, uint8_t upper = 127) {
@@ -157,4 +127,23 @@ class I2CBus {
gpio_num_t _scl = GPIO_NUM_NC;
uint32_t _freq = 100000;
bool _initialized = false;
i2c_master_bus_handle_t _bus = NULL;
i2c_master_dev_handle_t _dev = NULL;
uint8_t _dev_addr = 0xFF;
esp_err_t ensureDevice(uint8_t addr) {
if (_dev && _dev_addr == addr) return ESP_OK;
if (_dev) {
i2c_master_bus_rm_device(_dev);
_dev = NULL;
}
i2c_device_config_t dev_cfg = {};
dev_cfg.dev_addr_length = I2C_ADDR_BIT_LEN_7;
dev_cfg.device_address = addr;
dev_cfg.scl_speed_hz = _freq;
esp_err_t err = i2c_master_bus_add_device(_bus, &dev_cfg, &_dev);
if (err == ESP_OK) _dev_addr = addr;
return err;
}
};
+7 -60
View File
@@ -4,10 +4,6 @@
#include <features.h>
#include <peripherals/sensor.hpp>
#if FT_ENABLED(USE_ICM20948)
#include "ICM_20948.h"
#endif
#if FT_ENABLED(USE_MPU6050)
#include <peripherals/drivers/mpu6050.h>
#endif
@@ -24,7 +20,7 @@ struct IMUAnglesMsg {
class IMU : public SensorBase<IMUAnglesMsg> {
public:
bool initialize(void* _arg = nullptr) override {
bool initialize() override {
#if FT_ENABLED(USE_MPU6050)
_msg.success = _imu.begin();
if (!_msg.success) {
@@ -39,43 +35,13 @@ class IMU : public SensorBase<IMUAnglesMsg> {
ESP_LOGE("IMU", "BNO055 initialization failed");
return false;
}
#endif
#if FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_ICM20948_SPIMODE) > 0
#define ICM_20948_USE_DMP // TODO: Move to features.ini
SPI_PORT.begin(SPI_SCK, SPI_MISO, SPI_MOSI, -1); // TODO: Move to global spi start
_imu = (ICM_20948_SPI*)_arg;
#ifndef ICM20948_ALIVE
#define ICM20948_ALIVE
_imu->begin(ICM20948_SPI_CS, SPI_PORT); ESP_LOGI("IMU", "Beginning ICM20948 in SPI mode");
_imu->initializeDMP();
#endif
#else
_imu = (ICM_20948_I2C*)_arg;
#ifndef ICM20948_ALIVE
#define ICM20948_ALIVE
_imu->begin(Wire, 1, 0xFF); ESP_LOGI("IMU", "Beginning ICM20948 in I2C mode");
#endif
#endif
if (_imu->status != ICM_20948_Stat_Ok){ ESP_LOGW("IMU", "Failed to start ICM20948: begin failed"); return false; }
_imu->setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Continuous);
if (_imu->status != ICM_20948_Stat_Ok){ ESP_LOGW("IMU", "Failed to start ICM20948: set sample failed"); return false; }
ICM_20948_fss_t myFSS;
myFSS.a = gpm2;
myFSS.g = dps250;
_imu->setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS);
if (_imu->status != ICM_20948_Stat_Ok){ ESP_LOGW("IMU", "Failed to start ICM20948: set full scale failed"); return false; }
// TODO: Setup low pass filter config
_msg.success = true;
ESP_LOGI("IMU", "BNO055 initialized successfully");
#endif
return _msg.success;
}
bool update() override {
//if (!_msg.success) return false;
if (!_msg.success) return false;
#if FT_ENABLED(USE_MPU6050)
if (!_imu.update()) return false;
_msg.rpy[0] = _imu.getYaw();
@@ -83,22 +49,11 @@ class IMU : public SensorBase<IMUAnglesMsg> {
_msg.rpy[2] = _imu.getRoll();
_msg.temperature = _imu.getTemperature();
#endif
#if FT_ENABLED(USE_ICM20948)
#ifndef ICM20948_GET_AGMT_UPDATED_ONCE_PER_LOOP
#define ICM20948_GET_AGMT_UPDATED_ONCE_PER_LOOP
if (_imu->dataReady())
{
_imu->getAGMT();
} else {
return false;
}
#endif
_msg.rpy[0] = _imu->accX();
_msg.rpy[1] = _imu->accY();
_msg.rpy[2] = _imu->accZ();
#endif
#if FT_ENABLED(USE_BNO055)
if (!_imu.update()) return false;
_msg.rpy[0] = _imu.getHeading();
_msg.rpy[1] = _imu.getPitch();
_msg.rpy[2] = _imu.getRoll();
#endif
return true;
}
@@ -133,12 +88,4 @@ class IMU : public SensorBase<IMUAnglesMsg> {
#if FT_ENABLED(USE_BNO055)
BNO055Driver _imu;
#endif
#if FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_ICM20948_SPIMODE) > 0
ICM_20948_SPI* _imu;
#else
//#define WIRE_PORT Wire
ICM_20948_I2C* _imu;
#endif
#endif
};
+77 -23
View File
@@ -1,56 +1,110 @@
#ifndef LEDService_h
#define LEDService_h
#include <FastLED.h>
#include <sdkconfig.h>
#include <driver/rmt_tx.h>
#include <led_strip.h>
#include <led_strip_rmt.h>
#include <wifi/wifi_idf.h>
#include <utils/timing.h>
#include <esp_log.h>
#ifndef WS2812_PIN
#if CONFIG_IDF_TARGET_ESP32P4
#define WS2812_PIN 27
#else
#define WS2812_PIN 12
#endif
#endif
#ifndef WS2812_NUM_LEDS
#define WS2812_NUM_LEDS 1 + 12
#define WS2812_NUM_LEDS 13
#endif
#define COLOR_ORDER GRB
#define CHIPSET WS2811
class LEDService {
private:
CRGB leds[WS2812_NUM_LEDS];
CRGBPalette16 currentPalette;
TBlendType currentBlending;
led_strip_handle_t led_strip = nullptr;
int _brightness = 255;
int direction = 1;
bool initialized = false;
struct RGB {
uint8_t r, g, b;
};
RGB oceanColor = {0, 119, 190};
RGB forestColor = {34, 139, 34};
public:
LEDService() {
FastLED.addLeds<CHIPSET, WS2812_PIN, COLOR_ORDER>(leds, WS2812_NUM_LEDS).setCorrection(TypicalLEDStrip);
currentPalette = OceanColors_p;
currentBlending = LINEARBLEND;
LEDService() {}
~LEDService() {
if (initialized && led_strip) {
led_strip_del(led_strip);
}
}
void begin() {
if (initialized) return;
led_strip_config_t strip_config = {
.strip_gpio_num = WS2812_PIN,
.max_leds = WS2812_NUM_LEDS,
.led_pixel_format = LED_PIXEL_FORMAT_GRB,
.led_model = LED_MODEL_WS2812,
.flags = {.invert_out = false},
};
led_strip_rmt_config_t rmt_config = {
.clk_src = RMT_CLK_SRC_DEFAULT,
.resolution_hz = 10 * 1000 * 1000,
.mem_block_symbols = 64,
.flags = {.with_dma = false},
};
esp_err_t err = led_strip_new_rmt_device(&strip_config, &rmt_config, &led_strip);
if (err == ESP_OK) {
initialized = true;
led_strip_clear(led_strip);
ESP_LOGI("LEDService", "LED strip initialized on GPIO %d", WS2812_PIN);
} else {
ESP_LOGE("LEDService", "Failed to initialize LED strip: %s", esp_err_to_name(err));
}
}
~LEDService() {}
void loop() {
if (!initialized) return;
EXECUTE_EVERY_N_MS(1000 / 60, {
if (_brightness >= 200) direction = -5;
if (_brightness <= 50) direction = 5;
_brightness += direction;
if (WiFi.isConnected()) {
fillFromPallette(OceanColors_p, 0);
} else {
fillFromPallette(ForestColors_p, 128);
RGB color = WiFi.isConnected() ? oceanColor : forestColor;
uint8_t r = (color.r * _brightness) / 255;
uint8_t g = (color.g * _brightness) / 255;
uint8_t b = (color.b * _brightness) / 255;
for (int i = 0; i < WS2812_NUM_LEDS; ++i) {
led_strip_set_pixel(led_strip, i, r, g, b);
}
FastLED.show();
led_strip_refresh(led_strip);
});
}
void fillFromPallette(CRGBPalette16 colorPalette, uint8_t colorIndex) {
CRGB color = ColorFromPalette(colorPalette, colorIndex, _brightness, currentBlending);
void setColor(uint8_t r, uint8_t g, uint8_t b) {
if (!initialized) return;
for (int i = 0; i < WS2812_NUM_LEDS; ++i) {
leds[i] = color;
led_strip_set_pixel(led_strip, i, r, g, b);
}
led_strip_refresh(led_strip);
}
void clear() {
if (!initialized) return;
led_strip_clear(led_strip);
}
};
#endif
#endif
+13 -66
View File
@@ -12,63 +12,23 @@ struct MagnetometerMsg {
class Magnetometer : public SensorBase<MagnetometerMsg> {
public:
bool initialize(void* _arg) override {
#if FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_ICM20948_SPIMODE) > 0
SPI_PORT.begin(SPI_SCK, SPI_MISO, SPI_MOSI, -1);
_mag = (ICM_20948_SPI*)_arg;
#ifndef ICM20948_ALIVE
#define ICM20948_ALIVE
_imu->begin(ICM20948_SPI_CS, SPI_PORT); ESP_LOGI("Magnetometer", "Beginning ICM20948 in SPI mode");
#endif
#else
_mag = (ICM_20948_I2C*)_arg;
#ifndef ICM20948_ALIVE
#define ICM20948_ALIVE
if (!_mag->isConnected()) { _mag->begin(Wire, 1, 0xFF); ESP_LOGI("Magnetometer", "Beginning ICM20948 in I2C mode"); }
#endif
#endif
if (_mag->status != ICM_20948_Stat_Ok){ return false; }
_mag->startupMagnetometer();
if (_mag->status != ICM_20948_Stat_Ok){ return false; }
_msg.success = true;
#elif FT_ENABLED(USE_HMC5883)
_msg.success = _mag.begin();
#endif
bool initialize() override {
_msg.success = _mag.begin();
if (_msg.success) {
ESP_LOGI("MAG", "HMC5883L initialized successfully");
} else {
ESP_LOGE("MAG", "HMC5883L initialization failed");
}
return _msg.success;
}
bool update() override {
if (!_msg.success) return false;
#if FT_ENABLED(USE_ICM20948)
#ifndef ICM20948_GET_AGMT_UPDATED_ONCE_PER_LOOP
#define ICM20948_GET_AGMT_UPDATED_ONCE_PER_LOOP
if (_imu->dataReady())
{
_imu->getAGMT();
} else {
return false;
}
#endif
_msg.rpy[0] = _mag->magX();
_msg.rpy[1] = _mag->magY();
_msg.rpy[2] = _mag->magZ();
#elif FT_ENABLED(USE_HMC5883)
sensors_event_t event;
bool updated = _mag.getEvent(&event);
if (!updated) return false;
_msg.rpy[0] = event.magnetic.x;
_msg.rpy[1] = event.magnetic.y;
_msg.rpy[2] = event.magnetic.z;
#endif
_msg.heading = atan2(_msg.rpy[1], _msg.rpy[0]); // atan2(y, x)
_msg.heading += declinationAngle;
if (_msg.heading < 0) _msg.heading += 2 * PI;
if (_msg.heading > 2 * PI) _msg.heading -= 2 * PI;
_msg.heading *= 180 / M_PI;
if (!_mag.update()) return false;
_msg.rpy[0] = _mag.getMagX();
_msg.rpy[1] = _mag.getMagY();
_msg.rpy[2] = _mag.getMagZ();
_msg.heading = _mag.getHeading();
return true;
}
@@ -78,18 +38,5 @@ class Magnetometer : public SensorBase<MagnetometerMsg> {
float getHeading() { return _msg.heading; }
private:
#if FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_ICM20948_SPIMODE) > 0
#define SPI_PORT SPI // TODO in periphearals_seetings.h
#define CS_PIN 2
ICM_20948_SPI* _mag;
#else
//#define WIRE_PORT Wire
ICM_20948_I2C* _mag;
#endif
#elif FT_ENABLED(USE_HMC5883)
Adafruit_HMC5883_Unified _mag {12345};
#endif
const float declinationAngle = 0.22;
HMC5883LDriver _mag;
};
+5 -3
View File
@@ -1,6 +1,6 @@
#pragma once
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <template/stateful_service.h>
#include <template/stateful_proto_endpoint.h>
#include <utils/math_utils.h>
@@ -12,7 +12,9 @@
#include <list>
#if FT_ENABLED(USE_USS)
#include <NewPing.h>
#endif
#include <peripherals/i2c_bus.h>
#include <peripherals/imu.h>
#include <peripherals/magnetometer.h>
@@ -74,10 +76,10 @@ class Peripherals : public StatefulService<PeripheralsConfiguration> {
inline void endTransaction() { xSemaphoreGiveRecursive(_accessMutex); }
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
IMU _imu;
#endif
#if FT_ENABLED(USE_HMC5883) || FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_HMC5883)
Magnetometer _mag;
#endif
#if FT_ENABLED(USE_BMP180)
+1 -1
View File
@@ -3,7 +3,7 @@
template <class T>
class SensorBase {
public:
virtual bool initialize(void* _arg) = 0;
virtual bool initialize() = 0;
virtual bool update() = 0;
virtual bool isActive() { return _msg.success; }
+8 -14
View File
@@ -2,7 +2,7 @@
#define ServoController_h
#include <peripherals/drivers/pca9685.h>
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <template/stateful_proto_endpoint.h>
#include <template/stateful_service.h>
#include <utils/math_utils.h>
@@ -24,22 +24,17 @@ inline ServoSettings ServoSettings_defaults() {
ServoSettings settings = {};
settings.servos_count = 12;
const api_Servo defaults[12] = {
{306, -1, 0, 2.0f, "Servo1"}, {306, 1, -45, 2.0f, "Servo2"},
{306, 1, 90, 2.0f, "Servo3"}, {306, -1, 0, 2.0f, "Servo4"},
{306, -1, 45, 2.0f, "Servo5"}, {306, -1, -90, 2.0f, "Servo6"},
{306, 1, 0, 2.0f, "Servo7"}, {306, 1, -45, 2.0f, "Servo8"},
{306, 1, 90, 2.0f, "Servo9"}, {306, 1, 0, 2.0f, "Servo10"},
{306, -1, 45, 2.0f, "Servo11"}, {306, -1, -90, 2.0f, "Servo12"}
};
{306, -1, 0, 2.0f, "Servo1"}, {306, 1, -45, 2.0f, "Servo2"}, {306, 1, 90, 2.0f, "Servo3"},
{306, -1, 0, 2.0f, "Servo4"}, {306, -1, 45, 2.0f, "Servo5"}, {306, -1, -90, 2.0f, "Servo6"},
{306, 1, 0, 2.0f, "Servo7"}, {306, 1, -45, 2.0f, "Servo8"}, {306, 1, 90, 2.0f, "Servo9"},
{306, 1, 0, 2.0f, "Servo10"}, {306, -1, 45, 2.0f, "Servo11"}, {306, -1, -90, 2.0f, "Servo12"}};
for (int i = 0; i < 12; i++) {
settings.servos[i] = defaults[i];
}
return settings;
}
inline void ServoSettings_read(const ServoSettings &settings, ServoSettings &proto) {
proto = settings;
}
inline void ServoSettings_read(const ServoSettings &settings, ServoSettings &proto) { proto = settings; }
inline StateUpdateResult ServoSettings_update(const ServoSettings &proto, ServoSettings &settings) {
settings = proto;
@@ -52,9 +47,8 @@ class ServoController : public StatefulService<ServoSettings> {
: protoEndpoint(ServoSettings_read, ServoSettings_update, this,
API_REQUEST_EXTRACTOR(servo_settings, ServoSettings),
API_RESPONSE_ASSIGNER(servo_settings, ServoSettings)),
_persistence(ServoSettings_read, ServoSettings_update, this,
SERVO_SETTINGS_FILE, api_ServoSettings_fields, api_ServoSettings_size,
ServoSettings_defaults()) {}
_persistence(ServoSettings_read, ServoSettings_update, this, SERVO_SETTINGS_FILE, api_ServoSettings_fields,
api_ServoSettings_size, ServoSettings_defaults()) {}
void begin() {
_persistence.readFromFS();
+4 -7
View File
@@ -1,12 +1,11 @@
#pragma once
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <wifi/dns_server.h>
#include <template/state_result.h>
#include <platform_shared/api.pb.h>
#include <cstring>
#include <DNSServer.h>
#ifndef FACTORY_AP_PROVISION_MODE
#define FACTORY_AP_PROVISION_MODE api_APProvisionMode_AP_MODE_DISCONNECTED
#endif
@@ -77,11 +76,9 @@ inline APSettings APSettings_defaults() {
return settings;
}
inline void APSettings_read(const APSettings &settings, APSettings &proto) {
proto = settings;
}
inline void APSettings_read(const APSettings &settings, APSettings &proto) { proto = settings; }
inline StateUpdateResult APSettings_update(const APSettings &proto, APSettings &settings) {
settings = proto;
return StateUpdateResult::CHANGED;
}
}
+8 -3
View File
@@ -1,15 +1,20 @@
#pragma once
#include <template/state_result.h>
#include <sdkconfig.h>
#include <platform_shared/api.pb.h>
#if !CONFIG_IDF_TARGET_ESP32P4
#include <esp_camera.h>
#else
#define PIXFORMAT_JPEG 0
#define FRAMESIZE_VGA 0
#define GAINCEILING_2X 0
#endif
namespace Camera {
// Use proto type directly as settings type
using CameraSettings = api_CameraSettings;
// Default factory settings
inline CameraSettings CameraSettings_defaults() {
CameraSettings settings = api_CameraSettings_init_zero;
settings.pixformat = PIXFORMAT_JPEG;
-1
View File
@@ -1,4 +1,3 @@
#include <Arduino.h>
#include <template/state_result.h>
#include <ArduinoJson.h>
#include <string>
+4 -14
View File
@@ -1,20 +1,9 @@
#pragma once
#include <template/state_result.h>
#include <sdkconfig.h>
#include <platform_shared/api.pb.h>
/*
* I2C software connection
*/
#ifndef SDA_PIN
#define SDA_PIN SDA
#endif
#ifndef SCL_PIN
#define SCL_PIN SCL
#endif
#ifndef I2C_FREQUENCY
#define I2C_FREQUENCY 400000UL
#endif
#include <global.h>
// Use proto types directly
using PinConfig = api_PinConfig;
@@ -35,7 +24,8 @@ inline void PeripheralsConfiguration_read(const PeripheralsConfiguration& settin
proto = settings;
}
inline StateUpdateResult PeripheralsConfiguration_update(const PeripheralsConfiguration& proto, PeripheralsConfiguration& settings) {
inline StateUpdateResult PeripheralsConfiguration_update(const PeripheralsConfiguration& proto,
PeripheralsConfiguration& settings) {
settings = proto;
return StateUpdateResult::CHANGED;
}
+3 -4
View File
@@ -1,6 +1,6 @@
#pragma once
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <template/state_result.h>
#include <platform_shared/api.pb.h>
#include <cstring>
@@ -42,6 +42,7 @@ inline WiFiSettings WiFiSettings_defaults() {
strncpy(settings.hostname, FACTORY_WIFI_HOSTNAME, sizeof(settings.hostname) - 1);
settings.priority_rssi = true;
settings.wifi_networks_count = 0;
settings.selected_network = 0;
if (strlen(FACTORY_WIFI_SSID) > 0) {
settings.wifi_networks[0] = WiFiNetwork_defaults();
settings.wifi_networks_count = 1;
@@ -49,9 +50,7 @@ inline WiFiSettings WiFiSettings_defaults() {
return settings;
}
inline void WiFiSettings_read(const WiFiSettings &settings, WiFiSettings &proto) {
proto = settings;
}
inline void WiFiSettings_read(const WiFiSettings &settings, WiFiSettings &proto) { proto = settings; }
inline StateUpdateResult WiFiSettings_update(const WiFiSettings &proto, WiFiSettings &settings) {
settings = proto;
+2 -3
View File
@@ -1,8 +1,8 @@
#pragma once
#include <ESPmDNS.h>
#include <mdns.h>
#include <esp_http_server.h>
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <filesystem.h>
#include <global.h>
#include <esp_timer.h>
@@ -20,7 +20,6 @@ esp_err_t handleSleep(httpd_req_t *request);
void reset();
void restart();
void sleep();
void status(JsonObject &root);
void getAnalytics(socket_message_AnalyticsData &analytics);
void getStaticSystemInformation(socket_message_StaticSystemInformation &info);
+81 -60
View File
@@ -1,76 +1,102 @@
#ifndef FSPersistence_h
#define FSPersistence_h
#pragma once
/**
* ESP32 SvelteKit
*
* A simple, secure and extensible framework for IoT projects for ESP32 platforms
* with responsive Sveltekit front-end built with TailwindCSS and DaisyUI.
* https://github.com/theelims/ESP32-sveltekit
*
* Copyright (C) 2018 - 2023 rjwats
* Copyright (C) 2023 theelims
* Copyright (C) 2025 runeharlyk
*
* All Rights Reserved. This software may be modified and distributed under
* the terms of the LGPL v3 license. See the LICENSE file for details.
**/
#include <FS.h>
#include <template/stateful_service.h>
#include <template/state_result.h>
#include <filesystem.h>
#include <pb_encode.h>
#include <pb_decode.h>
#include <cstdio>
#include <sys/stat.h>
#include <esp_log.h>
static const char *TAG_PERSISTENCE = "FSPersistencePB";
template <class T>
class FSPersistence {
class FSPersistencePB {
public:
FSPersistence(JsonStateReader<T> stateReader, JsonStateUpdater<T> stateUpdater, StatefulService<T> *statefulService,
const char *filePath)
using ProtoStateReader = std::function<void(const T &, T &)>;
using ProtoStateUpdater = std::function<StateUpdateResult(const T &, T &)>;
FSPersistencePB(ProtoStateReader stateReader, ProtoStateUpdater stateUpdater, StatefulService<T> *statefulService,
const char *filePath, const pb_msgdesc_t *msgDescriptor, size_t maxSize, const T &defaultState)
: _stateReader(stateReader),
_stateUpdater(stateUpdater),
_statefulService(statefulService),
_filePath(filePath),
_msgDescriptor(msgDescriptor),
_maxSize(maxSize),
_defaultState(defaultState),
_updateHandlerId(0) {
enableUpdateHandler();
}
void readFromFS() {
File settingsFile = _fs->open(_filePath, "r");
FILE *file = fopen(_filePath, "rb");
if (settingsFile) {
JsonDocument jsonDocument;
DeserializationError error = deserializeJson(jsonDocument, settingsFile);
if (error == DeserializationError::Ok) {
JsonVariant jsonObject = jsonDocument.as<JsonVariant>();
_statefulService->updateWithoutPropagation(jsonObject, _stateUpdater);
settingsFile.close();
return;
if (file) {
fseek(file, 0, SEEK_END);
size_t fileSize = ftell(file);
fseek(file, 0, SEEK_SET);
if (fileSize > 0 && fileSize <= _maxSize) {
uint8_t *buffer = new uint8_t[fileSize];
size_t bytesRead = fread(buffer, 1, fileSize, file);
fclose(file);
if (bytesRead == fileSize) {
T *protoMsg = new T();
*protoMsg = {};
pb_istream_t stream = pb_istream_from_buffer(buffer, bytesRead);
if (pb_decode(&stream, _msgDescriptor, protoMsg)) {
_statefulService->updateWithoutPropagation(
[this, protoMsg](T &state) { return _stateUpdater(*protoMsg, state); });
delete protoMsg;
delete[] buffer;
return;
}
delete protoMsg;
}
delete[] buffer;
} else {
fclose(file);
}
settingsFile.close();
}
// If we reach here we have not been successful in loading the config
// and hard-coded defaults are now applied. The settings are then
// written back to the file system so the defaults persist between
// resets. This last step is required as in some cases defaults contain
// randomly generated values which would otherwise be modified on reset.
applyDefaults();
writeToFS();
}
bool writeToFS() {
JsonDocument jsonDocument;
JsonVariant jsonObject = jsonDocument.to<JsonVariant>();
_statefulService->read(jsonObject, _stateReader);
uint8_t *buffer = new uint8_t[_maxSize];
pb_ostream_t stream = pb_ostream_from_buffer(buffer, _maxSize);
T *protoMsg = new T();
*protoMsg = {};
_statefulService->read([this, protoMsg](const T &state) { _stateReader(state, *protoMsg); });
bool encodeSuccess = pb_encode(&stream, _msgDescriptor, protoMsg);
delete protoMsg;
if (!encodeSuccess) {
delete[] buffer;
return false;
}
mkdirs();
File file = _fs->open(_filePath, "w");
FILE *file = fopen(_filePath, "wb");
if (!file) {
ESP_LOGE(TAG_PERSISTENCE, "Failed to open file for writing: %s", _filePath);
delete[] buffer;
return false;
}
if (!file) return false;
size_t written = fwrite(buffer, 1, stream.bytes_written, file);
fclose(file);
delete[] buffer;
serializeJson(jsonDocument, file);
file.close();
return true;
return written == stream.bytes_written;
}
void disableUpdateHandler() {
@@ -87,34 +113,29 @@ class FSPersistence {
}
private:
JsonStateReader<T> _stateReader;
JsonStateUpdater<T> _stateUpdater;
ProtoStateReader _stateReader;
ProtoStateUpdater _stateUpdater;
StatefulService<T> *_statefulService;
FS *_fs {&ESP_FS};
const char *_filePath;
size_t _bufferSize;
const pb_msgdesc_t *_msgDescriptor;
size_t _maxSize;
T _defaultState;
HandlerId _updateHandlerId;
// We assume we have a _filePath with format
// "/directory1/directory2/filename" We create a directory for each missing
// parent
void mkdirs() {
std::string path(_filePath);
size_t index = 0;
while ((index = path.find('/', index + 1)) != std::string::npos) {
std::string segment = path.substr(0, index);
if (!_fs->exists(segment.c_str())) _fs->mkdir(segment.c_str());
struct stat st;
if (stat(segment.c_str(), &st) != 0) {
FileSystem::mkdirRecursive(segment.c_str());
}
}
}
protected:
// We assume the updater supplies sensible defaults if an empty object
// is supplied, this virtual function allows that to be changed.
virtual void applyDefaults() {
JsonDocument jsonDocument;
JsonVariant jsonObject = jsonDocument.as<JsonVariant>();
_statefulService->updateWithoutPropagation(jsonObject, _stateUpdater);
void applyDefaults() {
_statefulService->updateWithoutPropagation([this](T &state) { return _stateUpdater(_defaultState, state); });
}
};
#endif // end FSPersistence
@@ -1,144 +0,0 @@
#pragma once
#include <FS.h>
#include <template/stateful_service.h>
#include <template/state_result.h>
#include <filesystem.h>
#include <pb_encode.h>
#include <pb_decode.h>
/**
* Protobuf-based filesystem persistence for StatefulService.
*
* @tparam T The state type (should be a nanopb-generated struct like api_APSettings)
*/
template <class T>
class FSPersistencePB {
public:
// Formats are passed as referenced const (local variable) we want to read from, and a reference (proto) we write to
using ProtoStateReader = std::function<void(const T&, T&)>;
// Formats are passed as referenced const (new object) we read from, and a reference to the local variable we write to
using ProtoStateUpdater = std::function<StateUpdateResult(const T&, T&)>;
FSPersistencePB(ProtoStateReader stateReader, ProtoStateUpdater stateUpdater,
StatefulService<T> *statefulService, const char *filePath,
const pb_msgdesc_t *msgDescriptor, size_t maxSize,
const T &defaultState)
: _stateReader(stateReader),
_stateUpdater(stateUpdater),
_statefulService(statefulService),
_filePath(filePath),
_msgDescriptor(msgDescriptor),
_maxSize(maxSize),
_defaultState(defaultState),
_updateHandlerId(0) {
enableUpdateHandler();
}
void readFromFS() {
File file = _fs->open(_filePath, "r");
if (file) {
size_t fileSize = file.size();
if (fileSize > 0 && fileSize <= _maxSize) {
uint8_t *buffer = new uint8_t[fileSize];
size_t bytesRead = file.read(buffer, fileSize);
file.close();
if (bytesRead == fileSize) {
// Allocate on heap to avoid stack overflow with large proto messages
T *protoMsg = new T();
*protoMsg = {};
pb_istream_t stream = pb_istream_from_buffer(buffer, bytesRead);
if (pb_decode(&stream, _msgDescriptor, protoMsg)) {
_statefulService->updateWithoutPropagation(
[this, protoMsg](T &state) { return _stateUpdater(*protoMsg, state); });
delete protoMsg;
delete[] buffer;
return;
}
delete protoMsg;
}
delete[] buffer;
} else {
file.close();
}
}
applyDefaults();
writeToFS();
}
bool writeToFS() {
uint8_t *buffer = new uint8_t[_maxSize];
pb_ostream_t stream = pb_ostream_from_buffer(buffer, _maxSize);
// Allocate on heap to avoid stack overflow with large proto messages
T *protoMsg = new T();
*protoMsg = {};
_statefulService->read([this, protoMsg](const T &state) { _stateReader(state, *protoMsg); });
bool encodeSuccess = pb_encode(&stream, _msgDescriptor, protoMsg);
delete protoMsg;
if (!encodeSuccess) {
delete[] buffer;
return false;
}
mkdirs();
File file = _fs->open(_filePath, "w");
if (!file) {
delete[] buffer;
return false;
}
size_t written = file.write(buffer, stream.bytes_written);
file.close();
delete[] buffer;
return written == stream.bytes_written;
}
void disableUpdateHandler() {
if (_updateHandlerId) {
_statefulService->removeUpdateHandler(_updateHandlerId);
_updateHandlerId = 0;
}
}
void enableUpdateHandler() {
if (!_updateHandlerId) {
_updateHandlerId = _statefulService->addUpdateHandler(
[&](const std::string &originId) { writeToFS(); });
}
}
private:
ProtoStateReader _stateReader;
ProtoStateUpdater _stateUpdater;
StatefulService<T> *_statefulService;
FS *_fs{&ESP_FS};
const char *_filePath;
const pb_msgdesc_t *_msgDescriptor;
size_t _maxSize;
T _defaultState;
HandlerId _updateHandlerId;
void mkdirs() {
std::string path(_filePath);
size_t index = 0;
while ((index = path.find('/', index + 1)) != std::string::npos) {
std::string segment = path.substr(0, index);
if (!_fs->exists(segment.c_str())) _fs->mkdir(segment.c_str());
}
}
protected:
void applyDefaults() {
_statefulService->updateWithoutPropagation(
[this](T &state) { return _stateUpdater(_defaultState, state); });
}
};
+5 -29
View File
@@ -1,8 +1,5 @@
#pragma once
#include <Arduino.h>
#include <ArduinoJson.h>
#include <list>
#include <functional>
#include <freertos/FreeRTOS.h>
@@ -11,19 +8,13 @@
#include <template/state_result.h>
template <typename T>
using JsonStateUpdater = std::function<StateUpdateResult(JsonVariant &root, T &settings)>;
template <typename T>
using JsonStateReader = std::function<void(T &settings, JsonVariant &root)>;
using HandlerId = size_t;
using StateUpdateCallback = std::function<void(const std::string &originId)>;
using StateHookCallback = std::function<void(const std::string &originId, StateUpdateResult &result)>;
class HandlerBase {
protected:
static inline HandlerId nextId_ = 1; // Start from 1, 0 is invalid
static inline HandlerId nextId_ = 1;
HandlerId id_;
bool allowRemove_;
@@ -99,31 +90,16 @@ class StatefulService {
return result;
}
StateUpdateResult update(JsonVariant &jsonObject, JsonStateUpdater<T> stateUpdater, const std::string &originId) {
lock();
StateUpdateResult result = stateUpdater(jsonObject, state_);
unlock();
notifyStateChange(originId, result);
return result;
}
StateUpdateResult updateWithoutPropagation(JsonVariant &jsonObject, JsonStateUpdater<T> stateUpdater) {
lock();
StateUpdateResult result = stateUpdater(jsonObject, state_);
unlock();
return result;
}
void read(std::function<void(T &)> stateReader) {
lock();
stateReader(state_);
unlock();
}
void read(JsonVariant &jsonObject, JsonStateReader<T> stateReader) {
lock();
stateReader(state_, jsonObject);
unlock();
void read(std::function<void(const T &)> stateReader) const {
const_cast<StatefulService *>(this)->lock();
stateReader(state_);
const_cast<StatefulService *>(this)->unlock();
}
void callUpdateHandlers(const std::string &originId) {
+76
View File
@@ -0,0 +1,76 @@
#pragma once
#include <cstdint>
#include <cstring>
#include <string>
#include <esp_netif.h>
class IPAddress {
public:
IPAddress() : _addr {0, 0, 0, 0} {}
IPAddress(uint8_t a, uint8_t b, uint8_t c, uint8_t d) : _addr {a, b, c, d} {}
IPAddress(uint32_t addr) {
_addr[0] = addr & 0xFF;
_addr[1] = (addr >> 8) & 0xFF;
_addr[2] = (addr >> 16) & 0xFF;
_addr[3] = (addr >> 24) & 0xFF;
}
IPAddress(const esp_ip4_addr_t& ip4) {
_addr[0] = ip4.addr & 0xFF;
_addr[1] = (ip4.addr >> 8) & 0xFF;
_addr[2] = (ip4.addr >> 16) & 0xFF;
_addr[3] = (ip4.addr >> 24) & 0xFF;
}
operator uint32_t() const {
return static_cast<uint32_t>(_addr[0]) | (static_cast<uint32_t>(_addr[1]) << 8) |
(static_cast<uint32_t>(_addr[2]) << 16) | (static_cast<uint32_t>(_addr[3]) << 24);
}
operator esp_ip4_addr_t() const {
esp_ip4_addr_t ip4;
ip4.addr = static_cast<uint32_t>(*this);
return ip4;
}
bool operator==(const IPAddress& other) const {
return _addr[0] == other._addr[0] && _addr[1] == other._addr[1] && _addr[2] == other._addr[2] &&
_addr[3] == other._addr[3];
}
bool operator!=(const IPAddress& other) const { return !(*this == other); }
uint8_t operator[](int index) const { return _addr[index]; }
uint8_t& operator[](int index) { return _addr[index]; }
bool fromString(const char* str) {
int parts[4];
if (sscanf(str, "%d.%d.%d.%d", &parts[0], &parts[1], &parts[2], &parts[3]) != 4) {
return false;
}
for (int i = 0; i < 4; i++) {
if (parts[i] < 0 || parts[i] > 255) return false;
_addr[i] = static_cast<uint8_t>(parts[i]);
}
return true;
}
std::string toString() const {
char buf[16];
snprintf(buf, sizeof(buf), "%d.%d.%d.%d", _addr[0], _addr[1], _addr[2], _addr[3]);
return std::string(buf);
}
const char* c_str() const {
static char buf[16];
snprintf(buf, sizeof(buf), "%d.%d.%d.%d", _addr[0], _addr[1], _addr[2], _addr[3]);
return buf;
}
private:
uint8_t _addr[4];
};
-45
View File
@@ -40,51 +40,6 @@
last_time = esp_timer_get_time() / 1000; \
}
#define CALLS_PER_SECOND_TIMED_START_TICK(name, function) \
static uint64_t name##_##function##_start = 0; \
static uint64_t name##_##function##_total_time = 0; \
static uint64_t name##_##function##_call_count = 0; \
name##_##function##_start = esp_timer_get_time();
#define CALLS_PER_SECOND_TIMED_END_TICK(name, function) \
name##_##function##_total_time += (esp_timer_get_time() - name##_##function##_start); \
name##_##function##_call_count++;
#define CALLS_PER_SECOND_TIMED_CALL(name, function, call) \
static uint64_t name##_##function##_total_time = 0; \
static uint64_t name##_##function##_call_count = 0; \
do { \
uint64_t name##_##function##_start = esp_timer_get_time(); \
call; \
name##_##function##_total_time += (esp_timer_get_time() - name##_##function##_start); \
name##_##function##_call_count++; \
} while (0)
#define CALLS_PER_SECOND_TIMED_FUNC_PRINT(name, function) \
if (name##_##function##_call_count > 0) { \
uint64_t avg = name##_##function##_total_time / name##_##function##_call_count; \
if (avg < 1000) { \
ESP_LOGI("Timing", " %s: %llu us (avg over %llu calls)", \
#function, avg, name##_##function##_call_count); \
} else { \
ESP_LOGI("Timing", " %s: %llu ms (avg over %llu calls)", \
#function, avg / 1000, name##_##function##_call_count); \
} \
name##_##function##_total_time = 0; \
name##_##function##_call_count = 0; \
}
#define CALLS_PER_SECOND_TIMED(name, ...) \
do { \
static uint64_t name##_last_print = 0; \
uint64_t name##_current_time = esp_timer_get_time() / 1000; \
if (name##_current_time - name##_last_print >= 1000) { \
ESP_LOGI("Timing", "=== %s Average Timings ===", #name); \
__VA_ARGS__ \
name##_last_print = name##_current_time; \
} \
} while (0)
#define WARN_IF_SLOW(name, period_ms) \
static uint64_t name##_slow_count = 0; \
static uint64_t name##_slow_last_time = 0; \
+144
View File
@@ -0,0 +1,144 @@
#pragma once
#include <lwip/sockets.h>
#include <lwip/netdb.h>
#include <esp_log.h>
#include <utils/ip_address.h>
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include <string>
#include <atomic>
#define DNS_PORT 53
#define DNS_MAX_PACKET_SIZE 512
class DNSServer {
public:
DNSServer() : _socket(-1), _running(false), _task(nullptr) {}
~DNSServer() { stop(); }
bool start(uint16_t port, const char* domainName, const IPAddress& resolvedIP) {
if (_running) return true;
_port = port;
_resolvedIP = resolvedIP;
_domainName = domainName ? domainName : "*";
_socket = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP);
if (_socket < 0) {
ESP_LOGE("DNSServer", "Failed to create socket");
return false;
}
int opt = 1;
setsockopt(_socket, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt));
struct timeval tv;
tv.tv_sec = 1;
tv.tv_usec = 0;
setsockopt(_socket, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(tv));
struct sockaddr_in serverAddr = {};
serverAddr.sin_family = AF_INET;
serverAddr.sin_addr.s_addr = INADDR_ANY;
serverAddr.sin_port = htons(_port);
if (bind(_socket, (struct sockaddr*)&serverAddr, sizeof(serverAddr)) < 0) {
ESP_LOGE("DNSServer", "Failed to bind socket");
close(_socket);
_socket = -1;
return false;
}
_running = true;
xTaskCreate(dnsTask, "dns_server", 4096, this, 3, &_task);
ESP_LOGI("DNSServer", "Started on port %d, resolving to %s", _port, _resolvedIP.toString().c_str());
return true;
}
void stop() {
_running = false;
if (_task) {
vTaskDelay(100 / portTICK_PERIOD_MS);
_task = nullptr;
}
if (_socket >= 0) {
close(_socket);
_socket = -1;
}
ESP_LOGI("DNSServer", "Stopped");
}
void processNextRequest() {}
private:
static void dnsTask(void* param) {
DNSServer* self = static_cast<DNSServer*>(param);
self->run();
vTaskDelete(nullptr);
}
void run() {
uint8_t buffer[DNS_MAX_PACKET_SIZE];
struct sockaddr_in clientAddr;
socklen_t clientAddrLen = sizeof(clientAddr);
while (_running) {
int len = recvfrom(_socket, buffer, DNS_MAX_PACKET_SIZE, 0, (struct sockaddr*)&clientAddr, &clientAddrLen);
if (len > 0) {
processRequest(buffer, len, &clientAddr);
}
}
}
void processRequest(uint8_t* buffer, int len, struct sockaddr_in* clientAddr) {
if (len < 12) return;
uint16_t flags = (buffer[2] << 8) | buffer[3];
if ((flags & 0x8000) != 0) return;
uint8_t response[DNS_MAX_PACKET_SIZE];
memcpy(response, buffer, len);
response[2] = 0x81;
response[3] = 0x80;
response[6] = 0x00;
response[7] = 0x01;
int responseLen = len;
response[responseLen++] = 0xC0;
response[responseLen++] = 0x0C;
response[responseLen++] = 0x00;
response[responseLen++] = 0x01;
response[responseLen++] = 0x00;
response[responseLen++] = 0x01;
response[responseLen++] = 0x00;
response[responseLen++] = 0x00;
response[responseLen++] = 0x00;
response[responseLen++] = 0x3C;
response[responseLen++] = 0x00;
response[responseLen++] = 0x04;
uint32_t ip = static_cast<uint32_t>(_resolvedIP);
response[responseLen++] = ip & 0xFF;
response[responseLen++] = (ip >> 8) & 0xFF;
response[responseLen++] = (ip >> 16) & 0xFF;
response[responseLen++] = (ip >> 24) & 0xFF;
sendto(_socket, response, responseLen, 0, (struct sockaddr*)clientAddr, sizeof(*clientAddr));
}
int _socket;
uint16_t _port;
IPAddress _resolvedIP;
std::string _domainName;
std::atomic<bool> _running;
TaskHandle_t _task;
};
+127
View File
@@ -0,0 +1,127 @@
#pragma once
#include <esp_wifi.h>
#include <esp_event.h>
#include <esp_netif.h>
#include <esp_log.h>
#include <nvs_flash.h>
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include <freertos/event_groups.h>
#include <utils/ip_address.h>
#include <string>
#include <cstring>
#include <functional>
#include <vector>
typedef enum {
WL_NO_SHIELD = 255,
WL_IDLE_STATUS = 0,
WL_NO_SSID_AVAIL = 1,
WL_SCAN_COMPLETED = 2,
WL_CONNECTED = 3,
WL_CONNECT_FAILED = 4,
WL_CONNECTION_LOST = 5,
WL_DISCONNECTED = 6
} wl_status_t;
typedef enum {
WIFI_AUTH_OPEN_IDF = 0,
WIFI_AUTH_WEP_IDF,
WIFI_AUTH_WPA_PSK_IDF,
WIFI_AUTH_WPA2_PSK_IDF
} wifi_enc_type_t;
using WiFiEventCb = std::function<void(int32_t event, void* event_data)>;
struct WiFiEventHandler {
int32_t event_id;
WiFiEventCb callback;
};
class WiFiClass {
public:
WiFiClass();
~WiFiClass();
bool init();
bool mode(wifi_mode_t mode);
wifi_mode_t getMode();
bool begin(const char* ssid, const char* password = nullptr, int32_t channel = 0, const uint8_t* bssid = nullptr);
bool disconnect(bool wifiOff = false);
bool reconnect();
bool config(IPAddress local_ip, IPAddress gateway, IPAddress subnet, IPAddress dns1 = IPAddress(),
IPAddress dns2 = IPAddress());
bool setHostname(const char* hostname);
const char* getHostname();
wl_status_t status();
bool isConnected();
IPAddress localIP();
IPAddress subnetMask();
IPAddress gatewayIP();
IPAddress dnsIP(uint8_t dns_no = 0);
std::string macAddress();
std::string SSID();
std::string BSSIDstr();
int32_t RSSI();
uint8_t channel();
int16_t scanNetworks(bool async = false);
int16_t scanComplete();
void scanDelete();
std::string SSID(uint8_t i);
int32_t RSSI(uint8_t i);
wifi_enc_type_t encryptionType(uint8_t i);
std::string BSSIDstr(uint8_t i);
int32_t channel(uint8_t i);
void getNetworkInfo(uint8_t i, std::string& ssid, uint8_t& encType, int32_t& rssi, uint8_t*& bssid, int32_t& ch);
bool softAP(const char* ssid, const char* password = nullptr, int channel = 1, bool ssid_hidden = false,
int max_connection = 4);
bool softAPConfig(IPAddress local_ip, IPAddress gateway, IPAddress subnet);
bool softAPdisconnect(bool wifiOff = false);
IPAddress softAPIP();
std::string softAPmacAddress();
uint8_t softAPgetStationNum();
bool setAutoReconnect(bool autoReconnect);
bool persistent(bool persistent);
bool setTxPower(int8_t power);
void onEvent(WiFiEventCb callback, int32_t event_id);
private:
static void eventHandler(void* arg, esp_event_base_t event_base, int32_t event_id, void* event_data);
void dispatchEvent(int32_t event_id, void* event_data);
esp_netif_t* _sta_netif;
esp_netif_t* _ap_netif;
bool _initialized;
bool _autoReconnect;
bool _persistent;
wl_status_t _status;
wifi_mode_t _mode;
std::string _hostname;
wifi_ap_record_t* _scanResult;
uint16_t _scanCount;
int16_t _scanStatus;
std::vector<WiFiEventHandler> _eventHandlers;
IPAddress _sta_static_ip;
IPAddress _sta_static_gw;
IPAddress _sta_static_sn;
IPAddress _sta_static_dns1;
IPAddress _sta_static_dns2;
bool _useStaticIp;
};
extern WiFiClass WiFi;
+24 -20
View File
@@ -1,35 +1,22 @@
#pragma once
#include <esp_http_server.h>
#include <WiFi.h>
#include <ESPmDNS.h>
#include <wifi/wifi_idf.h>
#include <mdns.h>
#include <string>
#include <filesystem.h>
#include <utils/timing.h>
#include <template/stateful_service.h>
#include <template/stateful_persistence_pb.h>
#include <template/stateful_persistence.h>
#include <template/stateful_proto_endpoint.h>
#include <settings/wifi_settings.h>
#define WIFI_EVENT_STA_DISCONNECTED_IDF WIFI_EVENT_STA_DISCONNECTED
#define WIFI_EVENT_STA_STOP_IDF WIFI_EVENT_STA_STOP
#define IP_EVENT_STA_GOT_IP_IDF 1000
class WiFiService : public StatefulService<WiFiSettings> {
private:
void onStationModeDisconnected(WiFiEvent_t event, WiFiEventInfo_t info);
void onStationModeStop(WiFiEvent_t event, WiFiEventInfo_t info);
static void onStationModeGotIP(WiFiEvent_t event, WiFiEventInfo_t info);
FSPersistencePB<WiFiSettings> _persistence;
void reconfigureWiFiConnection();
void manageSTA();
void connectToWiFi();
void configureNetwork(WiFiNetwork &network);
unsigned long _lastConnectionAttempt;
bool _stopping;
constexpr static uint16_t reconnectDelay {10000};
public:
WiFiService();
~WiFiService();
@@ -38,6 +25,7 @@ class WiFiService : public StatefulService<WiFiSettings> {
void loop();
void setupMDNS(const char *hostname);
void selectNetwork(uint32_t index);
const char *getHostname() { return state().hostname; }
@@ -46,4 +34,20 @@ class WiFiService : public StatefulService<WiFiSettings> {
static esp_err_t getNetworkStatus(httpd_req_t *request);
StatefulProtoEndpoint<WiFiSettings, api_WifiSettings> protoEndpoint;
private:
void onStationModeDisconnected(int32_t event, void *event_data);
void onStationModeStop(int32_t event, void *event_data);
static void onStationModeGotIP(int32_t event, void *event_data);
FSPersistencePB<WiFiSettings> _persistence;
void reconfigureWiFiConnection();
void manageSTA();
void configureNetwork(WiFiNetwork &network);
unsigned long _lastConnectionAttempt;
bool _stopping;
constexpr static uint16_t reconnectDelay {10000};
};
+1
View File
@@ -3,3 +3,4 @@
#include "WWWData.h"
void mountStaticAssets(WebServer& s);
void mountSpaFallback(WebServer& s);
+8
View File
@@ -0,0 +1,8 @@
# Name, Type, SubType, Offset, Size, Flags
# 32MB Flash partition table for ESP32-P4
nvs, data, nvs, 0x9000, 0x5000,
otadata, data, ota, 0xe000, 0x2000,
app0, app, ota_0, 0x10000, 0xC80000,
app1, app, ota_1, 0xC90000, 0xC80000,
spiffs, data, spiffs, 0x1910000,0x6E0000,
coredump, data, coredump,0x1FF0000,0x10000,
1 # Name, Type, SubType, Offset, Size, Flags
2 # 32MB Flash partition table for ESP32-P4
3 nvs, data, nvs, 0x9000, 0x5000,
4 otadata, data, ota, 0xe000, 0x2000,
5 app0, app, ota_0, 0x10000, 0xC80000,
6 app1, app, ota_1, 0xC90000, 0xC80000,
7 spiffs, data, spiffs, 0x1910000,0x6E0000,
8 coredump, data, coredump,0x1FF0000,0x10000,
+1 -1
View File
@@ -114,7 +114,7 @@ def write_header():
with open(output_file, "w", newline="\n") as f:
f.write("#pragma once\n")
f.write("#include <Arduino.h>\n\n")
f.write("#include <compat/pgmspace.h>\n\n")
f.write(
"struct WebAsset { const char* uri; const char* mime; const uint8_t* data; uint32_t len; uint32_t etag; uint8_t gz; };\n")
f.write(
+36
View File
@@ -0,0 +1,36 @@
set(COMPONENT_REQUIRES
driver
esp_driver_i2c
esp_http_server
nvs_flash
esp_wifi
esp_event
esp_netif
mdns
esp_timer
esp_psram
spi_flash
littlefs
esp-dsp
)
if(IDF_TARGET STREQUAL "esp32p4")
list(APPEND COMPONENT_REQUIRES esp_wifi_remote esp_hosted esp_driver_cam esp_driver_isp esp_driver_jpeg espressif__esp_sccb_intf espressif__esp_cam_sensor)
else()
list(APPEND COMPONENT_REQUIRES esp32-camera)
endif()
idf_component_register(
SRC_DIRS
"."
"communication"
"peripherals"
"wifi"
"platform_shared"
"../../submodules/nanopb"
INCLUDE_DIRS
"../include"
"../../submodules/nanopb"
REQUIRES
${COMPONENT_REQUIRES}
)
+22 -21
View File
@@ -4,21 +4,26 @@
static const char *TAG = "APService";
APService::APService()
: protoEndpoint(APSettings_read, APSettings_update, this,
API_REQUEST_EXTRACTOR(ap_settings, api_APSettings),
: protoEndpoint(APSettings_read, APSettings_update, this, API_REQUEST_EXTRACTOR(ap_settings, api_APSettings),
API_RESPONSE_ASSIGNER(ap_settings, api_APSettings)),
_persistence(APSettings_read, APSettings_update, this,
AP_SETTINGS_FILE, api_APSettings_fields, api_APSettings_size,
APSettings_defaults()) {
_persistence(APSettings_read, APSettings_update, this, AP_SETTINGS_FILE, api_APSettings_fields,
api_APSettings_size, APSettings_defaults()),
_dnsServer(nullptr),
_lastManaged(0),
_reconfigureAp(false),
_recoveryMode(false) {
addUpdateHandler([&](const std::string &originId) { reconfigureAP(); }, false);
}
APService::~APService() {}
void APService::begin() {
_persistence.readFromFS();
APService::~APService() {
if (_dnsServer) {
delete _dnsServer;
_dnsServer = nullptr;
}
}
void APService::begin() { _persistence.readFromFS(); }
esp_err_t APService::getStatusProto(httpd_req_t *request) {
api_Response res = api_Response_init_zero;
res.status_code = 200;
@@ -30,15 +35,15 @@ esp_err_t APService::getStatusProto(httpd_req_t *request) {
void APService::statusProto(api_APStatus &proto) {
proto.status = getAPNetworkStatus();
proto.ip_address = static_cast<uint32_t>(WiFi.softAPIP());
String mac = WiFi.softAPmacAddress();
std::string mac = WiFi.softAPmacAddress();
strncpy(proto.mac_address, mac.c_str(), sizeof(proto.mac_address) - 1);
proto.mac_address[sizeof(proto.mac_address) - 1] = '\0';
proto.station_num = WiFi.softAPgetStationNum();
}
APNetworkStatus APService::getAPNetworkStatus() {
WiFiMode_t currentWiFiMode = WiFi.getMode();
bool apActive = currentWiFiMode == WIFI_AP || currentWiFiMode == WIFI_AP_STA;
wifi_mode_t currentWiFiMode = WiFi.getMode();
bool apActive = currentWiFiMode == WIFI_MODE_AP || currentWiFiMode == WIFI_MODE_APSTA;
if (apActive && state().provision_mode != AP_MODE_ALWAYS && WiFi.status() == WL_CONNECTED) {
return LINGERING;
}
@@ -64,13 +69,13 @@ void APService::loop() {
}
void APService::manageAP() {
WiFiMode_t currentWiFiMode = WiFi.getMode();
wifi_mode_t currentWiFiMode = WiFi.getMode();
if (state().provision_mode == AP_MODE_ALWAYS ||
(state().provision_mode == AP_MODE_DISCONNECTED && WiFi.status() != WL_CONNECTED) || _recoveryMode) {
if (_reconfigureAp || currentWiFiMode == WIFI_OFF || currentWiFiMode == WIFI_STA) {
if (_reconfigureAp || currentWiFiMode == WIFI_MODE_NULL || currentWiFiMode == WIFI_MODE_STA) {
startAP();
}
} else if ((currentWiFiMode == WIFI_AP || currentWiFiMode == WIFI_AP_STA) &&
} else if ((currentWiFiMode == WIFI_MODE_AP || currentWiFiMode == WIFI_MODE_APSTA) &&
(_reconfigureAp || !WiFi.softAPgetStationNum())) {
stopAP();
}
@@ -82,7 +87,7 @@ void APService::startAP() {
WiFi.softAPConfig(IPAddress(state().local_ip), IPAddress(state().gateway_ip), IPAddress(state().subnet_mask));
WiFi.softAP(state().ssid, state().password, state().channel, state().ssid_hidden, state().max_clients);
#if CONFIG_IDF_TARGET_ESP32C3
WiFi.setTxPower(WIFI_POWER_8_5dBm);
WiFi.setTxPower(8);
#endif
if (!_dnsServer) {
IPAddress apIp = WiFi.softAPIP();
@@ -103,8 +108,4 @@ void APService::stopAP() {
WiFi.softAPdisconnect(true);
}
void APService::handleDNS() {
if (_dnsServer) {
_dnsServer->processNextRequest();
}
}
void APService::handleDNS() {}
+1 -1
View File
@@ -278,7 +278,7 @@ esp_err_t WebServer::wsSendAll(const uint8_t* data, size_t len) {
}
esp_err_t WebServer::sendError(httpd_req_t* req, int status, const char* message) {
return send(req, status, (uint8_t*) message, strlen(message));
return send(req, status, (uint8_t*)message, strlen(message));
}
esp_err_t WebServer::sendOk(httpd_req_t* req) { return send(req, 200, nullptr, 0); }
+2 -5
View File
@@ -10,14 +10,11 @@ void printFeatureConfiguration() {
ESP_LOGI("Features", "USE_CAMERA: %s", USE_CAMERA ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_MOTION: %s", USE_MOTION ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_ICM20948: %s", USE_ICM20948 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_BNO055: %s", USE_BNO055 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_MPU6050: %s", USE_MPU6050 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_HMC5883: %s", USE_HMC5883 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_BMP180: %s", USE_BMP180 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_USS: %s", USE_USS ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_PAJ7620U2: %s", USE_PAJ7620U2 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_PCA9685: %s", USE_PCA9685 ? "enabled" : "disabled");
ESP_LOGI("Features", "USE_WS2812: %s", USE_WS2812 ? "enabled" : "disabled");
@@ -30,8 +27,8 @@ void printFeatureConfiguration() {
void features_request(const socket_message_FeaturesDataRequest& fd_req, socket_message_FeaturesDataResponse& fd_res) {
fd_res.camera = USE_CAMERA ? true : false;
fd_res.imu = (USE_MPU6050 || USE_BNO055 || USE_ICM20948) ? true : false;
fd_res.mag = (USE_HMC5883 || USE_BNO055 || USE_ICM20948) ? true : false;
fd_res.imu = (USE_MPU6050 || USE_BNO055) ? true : false;
fd_res.mag = (USE_HMC5883 || USE_BNO055) ? true : false;
fd_res.bmp = USE_BMP180 ? true : false;
fd_res.sonar = USE_USS ? true : false;
fd_res.servo = USE_PCA9685 ? true : false;
+206 -65
View File
@@ -3,13 +3,15 @@
#include <vector>
#include <cstring>
#include "utils/string_utils.hpp"
#include <esp_log.h>
#include <pb_encode.h>
#include <pb_decode.h>
static const char *TAG = "FileService";
static const char *TAG = "FileSystem";
namespace FileSystem {
// Storage for dynamically allocated FileEntry arrays
static std::vector<api_FileEntry*> allocatedEntries;
static std::vector<api_FileEntry *> allocatedEntries;
static void freeAllocatedEntries() {
for (auto ptr : allocatedEntries) {
@@ -18,67 +20,81 @@ static void freeAllocatedEntries() {
allocatedEntries.clear();
}
void listFilesProto(const std::string &directory, api_FileEntry *entry) {
File root = ESP_FS.open(directory.find("/") == 0 ? directory.c_str() : ("/" + directory).c_str());
if (!root.isDirectory()) {
static void listFilesProtoRecursive(const std::string &directory, api_FileEntry *entry) {
DIR *dir = opendir(directory.c_str());
if (!dir) {
entry->children_count = 0;
entry->children = nullptr;
return;
}
// First pass: count children
std::vector<File> files;
File file = root.openNextFile();
while (file) {
files.push_back(file);
file = root.openNextFile();
}
std::vector<std::string> names;
std::vector<bool> isDirs;
std::vector<size_t> sizes;
if (files.empty()) {
struct dirent *d;
while ((d = readdir(dir)) != nullptr) {
if (strcmp(d->d_name, ".") == 0 || strcmp(d->d_name, "..") == 0) continue;
std::string fullPath = directory + "/" + d->d_name;
struct stat st;
if (stat(fullPath.c_str(), &st) == 0) {
names.push_back(d->d_name);
isDirs.push_back(S_ISDIR(st.st_mode));
sizes.push_back(st.st_size);
}
}
closedir(dir);
if (names.empty()) {
entry->children_count = 0;
entry->children = nullptr;
return;
}
// Allocate children array
entry->children_count = files.size();
entry->children = new api_FileEntry[files.size()];
entry->children_count = names.size();
entry->children = new api_FileEntry[names.size()];
allocatedEntries.push_back(entry->children);
// Fill children
for (size_t i = 0; i < files.size(); i++) {
for (size_t i = 0; i < names.size(); i++) {
api_FileEntry &child = entry->children[i];
memset(&child, 0, sizeof(child));
std::string name = std::string(files[i].name());
strncpy(child.name, name.c_str(), sizeof(child.name) - 1);
strncpy(child.name, names[i].c_str(), sizeof(child.name) - 1);
child.name[sizeof(child.name) - 1] = '\0';
child.is_directory = files[i].isDirectory();
child.is_directory = isDirs[i];
if (child.is_directory) {
listFilesProto(name, &child);
std::string childPath = directory + "/" + names[i];
listFilesProtoRecursive(childPath, &child);
} else {
child.size = files[i].size();
child.size = sizes[i];
child.children_count = 0;
child.children = nullptr;
}
}
}
void listFilesProto(const std::string &directory, api_FileEntry *entry) {
std::string path = directory;
if (path.empty() || path[0] != '/') {
path = "/" + directory;
}
std::string fullPath = std::string(MOUNT_POINT) + path;
listFilesProtoRecursive(fullPath, entry);
}
esp_err_t getFilesProto(httpd_req_t *request) {
freeAllocatedEntries(); // Clean up any previous allocations
freeAllocatedEntries();
api_Response res = api_Response_init_zero;
res.status_code = 200;
res.which_payload = api_Response_file_list_tag;
// Create root entry
api_FileEntry rootEntry = api_FileEntry_init_zero;
strncpy(rootEntry.name, "root", sizeof(rootEntry.name) - 1);
rootEntry.is_directory = true;
listFilesProto("/", &rootEntry);
listFilesProtoRecursive(MOUNT_POINT, &rootEntry);
// Allocate entries array for FileList
res.payload.file_list.entries_count = 1;
res.payload.file_list.entries = new api_FileEntry[1];
allocatedEntries.push_back(res.payload.file_list.entries);
@@ -86,28 +102,146 @@ esp_err_t getFilesProto(httpd_req_t *request) {
esp_err_t result = WebServer::send(request, 200, res, api_Response_fields);
freeAllocatedEntries(); // Clean up after sending
freeAllocatedEntries();
return result;
}
bool init() {
esp_vfs_littlefs_conf_t conf = {
.base_path = MOUNT_POINT,
.partition_label = "spiffs",
.format_if_mount_failed = true,
.dont_mount = false,
};
esp_err_t ret = esp_vfs_littlefs_register(&conf);
if (ret != ESP_OK) {
if (ret == ESP_FAIL) {
ESP_LOGE(TAG, "Failed to mount or format filesystem");
} else if (ret == ESP_ERR_NOT_FOUND) {
ESP_LOGE(TAG, "Failed to find LittleFS partition");
} else {
ESP_LOGE(TAG, "Failed to initialize LittleFS (%s)", esp_err_to_name(ret));
}
return false;
}
size_t total = 0, used = 0;
ret = esp_littlefs_info("spiffs", &total, &used);
if (ret == ESP_OK) {
ESP_LOGI(TAG, "Partition size: total: %d, used: %d", total, used);
}
mkdirRecursive(FS_CONFIG_DIRECTORY);
return true;
}
bool fileExists(const char *filename) {
struct stat st;
return stat(filename, &st) == 0;
}
std::string readFile(const char *filename) {
FILE *f = fopen(filename, "r");
if (!f) {
return "";
}
fseek(f, 0, SEEK_END);
long size = ftell(f);
fseek(f, 0, SEEK_SET);
std::string content;
content.resize(size);
fread(&content[0], 1, size, f);
fclose(f);
return content;
}
bool writeFile(const char *filename, const char *content) {
FILE *f = fopen(filename, "w");
if (!f) {
ESP_LOGE(TAG, "Failed to open file for writing: %s", filename);
return false;
}
size_t len = strlen(content);
size_t written = fwrite(content, 1, len, f);
fclose(f);
return written == len;
}
bool writeFile(const char *filename, const uint8_t *content, size_t size) {
FILE *f = fopen(filename, "wb");
if (!f) {
ESP_LOGE(TAG, "Failed to open file for writing: %s", filename);
return false;
}
size_t written = fwrite(content, 1, size, f);
fclose(f);
return written == size;
}
bool mkdirRecursive(const char *path) {
char tmp[256];
char *p = nullptr;
size_t len;
snprintf(tmp, sizeof(tmp), "%s", path);
len = strlen(tmp);
if (tmp[len - 1] == '/') {
tmp[len - 1] = 0;
}
for (p = tmp + 1; *p; p++) {
if (*p == '/') {
*p = 0;
struct stat st;
if (stat(tmp, &st) != 0) {
if (::mkdir(tmp, 0755) != 0) {
ESP_LOGE(TAG, "Failed to create directory: %s", tmp);
return false;
}
}
*p = '/';
}
}
struct stat st;
if (stat(tmp, &st) != 0) {
if (::mkdir(tmp, 0755) != 0) {
ESP_LOGE(TAG, "Failed to create directory: %s", tmp);
return false;
}
}
return true;
}
esp_err_t getFiles(httpd_req_t *request) {
std::string files = listFiles("/");
std::string files = listFiles(MOUNT_POINT);
httpd_resp_set_type(request, "application/json");
return httpd_resp_send(request, files.c_str(), files.length());
}
esp_err_t getConfigFile(httpd_req_t *request) {
const char *uri = request->uri;
std::string path = "/config" + std::string(uri).substr(11);
if (!ESP_FS.exists(path.c_str())) {
std::string path = std::string(MOUNT_POINT) + "/config" + std::string(uri).substr(11);
if (!fileExists(path.c_str())) {
return WebServer::sendError(request, 404, "File not found");
}
File file = ESP_FS.open(path.c_str(), "r");
if (!file) {
return WebServer::sendError(request, 500, "Failed to open file");
std::string content = readFile(path.c_str());
if (content.empty()) {
return WebServer::sendError(request, 500, "Failed to read file");
}
String content = file.readString();
file.close();
if (ends_with(path, ".pb")) {
httpd_resp_set_type(request, "application/x-protobuf");
} else if (ends_with(path, ".json")) {
@@ -119,10 +253,11 @@ esp_err_t getConfigFile(httpd_req_t *request) {
}
esp_err_t handleDelete(httpd_req_t *request, const api_FileDeleteRequest &req) {
ESP_LOGI(TAG, "Deleting file: %s", req.path);
std::string fullPath = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Deleting file: %s", fullPath.c_str());
api_Response res = api_Response_init_zero;
if (deleteFile(req.path)) {
if (deleteFile(fullPath.c_str())) {
res.status_code = 200;
res.which_payload = api_Response_empty_message_tag;
return WebServer::send(request, 200, res, api_Response_fields);
@@ -132,10 +267,11 @@ esp_err_t handleDelete(httpd_req_t *request, const api_FileDeleteRequest &req) {
}
esp_err_t handleEdit(httpd_req_t *request, const api_FileEditRequest &req) {
ESP_LOGI(TAG, "Editing file: %s", req.path);
std::string fullPath = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Editing file: %s", fullPath.c_str());
api_Response res = api_Response_init_zero;
if (editFile(req.path, req.content->bytes, req.content->size)) {
if (editFile(fullPath.c_str(), req.content->bytes, req.content->size)) {
res.status_code = 200;
res.which_payload = api_Response_empty_message_tag;
return WebServer::send(request, 200, res, api_Response_fields);
@@ -144,52 +280,57 @@ esp_err_t handleEdit(httpd_req_t *request, const api_FileEditRequest &req) {
}
}
bool deleteFile(const char *filename) { return ESP_FS.remove(filename); }
bool deleteFile(const char *filename) { return remove(filename) == 0; }
std::string listFiles(const std::string &directory, bool isRoot) {
File root = ESP_FS.open(directory.find("/") == 0 ? directory.c_str() : ("/" + directory).c_str());
if (!root.isDirectory()) return "{}";
File file = root.openNextFile();
if (!file) {
DIR *dir = opendir(directory.c_str());
if (!dir) {
return isRoot ? "{ \"root\": {} }" : "{}";
}
std::string output = isRoot ? "{ \"root\": {" : "{";
bool first = true;
while (file) {
std::string name = std::string(file.name());
if (file.isDirectory()) {
output += "\"" + name + "\": " + listFiles(name, false);
} else {
output += "\"" + name + "\": " + std::to_string(file.size());
struct dirent *entry;
while ((entry = readdir(dir)) != nullptr) {
if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) {
continue;
}
File next = root.openNextFile();
if (next) output += ", ";
file = next;
if (!first) {
output += ", ";
}
first = false;
std::string fullPath = directory + "/" + entry->d_name;
struct stat st;
if (stat(fullPath.c_str(), &st) == 0) {
if (S_ISDIR(st.st_mode)) {
output += "\"" + std::string(entry->d_name) + "\": " + listFiles(fullPath, false);
} else {
output += "\"" + std::string(entry->d_name) + "\": " + std::to_string(st.st_size);
}
}
}
closedir(dir);
output += "}";
if (isRoot) output += "}";
return output;
}
bool editFile(const char *filename, const uint8_t *content, size_t size) {
File file = ESP_FS.open(filename, FILE_WRITE);
if (!file) return false;
bool editFile(const char *filename, const uint8_t *content, size_t size) { return writeFile(filename, content, size); }
file.write(content, size);
file.close();
return true;
}
bool editFile(const char *filename, const char *content) { return writeFile(filename, content); }
esp_err_t mkdir(httpd_req_t *request, const api_FileMkdirRequest &req) {
ESP_LOGI(TAG, "Creating directory: %s", req.path);
std::string fullPath = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Creating directory: %s", fullPath.c_str());
api_Response res = api_Response_init_zero;
if (ESP_FS.mkdir(req.path)) {
if (mkdirRecursive(fullPath.c_str())) {
res.status_code = 200;
res.which_payload = api_Response_empty_message_tag;
return WebServer::send(request, 200, res, api_Response_fields);
+77 -78
View File
@@ -1,9 +1,12 @@
#include <filesystem_ws.h>
#include <filesystem.h>
#include <pb_encode.h>
#include <pb_decode.h>
#include <esp_littlefs.h>
#include <esp_timer.h>
#include <esp_log.h>
#include <dirent.h>
#include <sys/stat.h>
#include <cstring>
static const char* TAG = "FileSystemWS";
@@ -29,7 +32,7 @@ void FileSystemHandler::cleanupExpiredTransfers() {
while (dlIt != downloads_.end()) {
if (now - dlIt->second.lastActivityTime > FS_TRANSFER_TIMEOUT_MS) {
if (dlIt->second.file) {
dlIt->second.file.close();
fclose(dlIt->second.file);
}
ESP_LOGW(TAG, "Download %u timed out", dlIt->first);
@@ -53,9 +56,9 @@ void FileSystemHandler::cleanupExpiredTransfers() {
while (ulIt != uploads_.end()) {
if (now - ulIt->second.lastActivityTime > FS_TRANSFER_TIMEOUT_MS) {
if (ulIt->second.file) {
ulIt->second.file.close();
fclose(ulIt->second.file);
}
ESP_FS.remove(ulIt->second.path.c_str());
remove(ulIt->second.path.c_str());
ESP_LOGW(TAG, "Upload %u timed out, deleted partial file", ulIt->first);
if (sendUploadCompleteCallback_) {
@@ -77,10 +80,11 @@ void FileSystemHandler::cleanupExpiredTransfers() {
socket_message_FSDeleteResponse FileSystemHandler::handleDelete(const socket_message_FSDeleteRequest& req) {
socket_message_FSDeleteResponse response = socket_message_FSDeleteResponse_init_zero;
std::string path(req.path);
std::string path = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Delete request: %s", path.c_str());
if (!ESP_FS.exists(path.c_str())) {
struct stat st;
if (stat(path.c_str(), &st) != 0) {
response.success = false;
strncpy(response.error, "File or directory not found", sizeof(response.error) - 1);
return response;
@@ -97,41 +101,45 @@ socket_message_FSDeleteResponse FileSystemHandler::handleDelete(const socket_mes
}
bool FileSystemHandler::deleteRecursive(const std::string& path) {
File file = ESP_FS.open(path.c_str());
if (!file) return false;
struct stat st;
if (stat(path.c_str(), &st) != 0) return false;
if (file.isDirectory()) {
File child = file.openNextFile();
while (child) {
std::string childPath = std::string(child.name());
child.close();
if (S_ISDIR(st.st_mode)) {
DIR* dir = opendir(path.c_str());
if (!dir) return false;
struct dirent* entry;
while ((entry = readdir(dir)) != nullptr) {
if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) {
continue;
}
std::string childPath = path + "/" + entry->d_name;
if (!deleteRecursive(childPath)) {
file.close();
closedir(dir);
return false;
}
child = file.openNextFile();
}
file.close();
return ESP_FS.rmdir(path.c_str());
closedir(dir);
return rmdir(path.c_str()) == 0;
} else {
file.close();
return ESP_FS.remove(path.c_str());
return remove(path.c_str()) == 0;
}
}
socket_message_FSMkdirResponse FileSystemHandler::handleMkdir(const socket_message_FSMkdirRequest& req) {
socket_message_FSMkdirResponse response = socket_message_FSMkdirResponse_init_zero;
std::string path(req.path);
std::string path = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Mkdir request: %s", path.c_str());
if (ESP_FS.exists(path.c_str())) {
struct stat st;
if (stat(path.c_str(), &st) == 0) {
response.success = false;
strncpy(response.error, "Path already exists", sizeof(response.error) - 1);
return response;
}
if (ESP_FS.mkdir(path.c_str())) {
if (FileSystem::mkdirRecursive(path.c_str())) {
response.success = true;
} else {
response.success = false;
@@ -142,32 +150,40 @@ socket_message_FSMkdirResponse FileSystemHandler::handleMkdir(const socket_messa
}
void FileSystemHandler::listDirectory(const std::string& path, socket_message_FSListResponse& response) {
File dir = ESP_FS.open(path.c_str());
if (!dir || !dir.isDirectory()) {
DIR* dir = opendir(path.c_str());
if (!dir) {
return;
}
File file = dir.openNextFile();
struct dirent* entry;
int fileCount = 0;
int dirCount = 0;
while (file && fileCount < 20 && dirCount < 20) { // Limit to match protobuf max_count
if (file.isDirectory()) {
while ((entry = readdir(dir)) != nullptr && fileCount < 20 && dirCount < 20) {
if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) {
continue;
}
std::string fullPath = path + "/" + entry->d_name;
struct stat st;
if (stat(fullPath.c_str(), &st) != 0) continue;
if (S_ISDIR(st.st_mode)) {
if (dirCount < 20) {
strncpy(response.directories[dirCount].name, file.name(),
strncpy(response.directories[dirCount].name, entry->d_name,
sizeof(response.directories[dirCount].name) - 1);
dirCount++;
}
} else {
if (fileCount < 20) {
strncpy(response.files[fileCount].name, file.name(), sizeof(response.files[fileCount].name) - 1);
response.files[fileCount].size = file.size();
strncpy(response.files[fileCount].name, entry->d_name, sizeof(response.files[fileCount].name) - 1);
response.files[fileCount].size = st.st_size;
fileCount++;
}
}
file = dir.openNextFile();
}
closedir(dir);
response.files_count = fileCount;
response.directories_count = dirCount;
}
@@ -175,12 +191,15 @@ void FileSystemHandler::listDirectory(const std::string& path, socket_message_FS
socket_message_FSListResponse FileSystemHandler::handleList(const socket_message_FSListRequest& req) {
socket_message_FSListResponse response = socket_message_FSListResponse_init_zero;
std::string path(req.path);
if (path.empty()) path = "/";
std::string path = std::string(MOUNT_POINT);
if (strlen(req.path) > 0 && req.path[0] != '\0') {
path += req.path;
}
ESP_LOGI(TAG, "List request: %s", path.c_str());
if (!ESP_FS.exists(path.c_str())) {
struct stat st;
if (stat(path.c_str(), &st) != 0) {
response.success = false;
strncpy(response.error, "Path not found", sizeof(response.error) - 1);
return response;
@@ -192,14 +211,12 @@ socket_message_FSListResponse FileSystemHandler::handleList(const socket_message
return response;
}
// ===== STREAMING DOWNLOAD =====
void FileSystemHandler::handleDownloadRequest(const socket_message_FSDownloadRequest& req, int clientId) {
std::string path(req.path);
std::string path = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Download request: %s", path.c_str());
// Validate file exists
if (!ESP_FS.exists(path.c_str())) {
struct stat st;
if (stat(path.c_str(), &st) != 0 || S_ISDIR(st.st_mode)) {
if (sendMetadataCallback_) {
socket_message_FSDownloadMetadata metadata = socket_message_FSDownloadMetadata_init_zero;
metadata.success = false;
@@ -209,8 +226,8 @@ void FileSystemHandler::handleDownloadRequest(const socket_message_FSDownloadReq
return;
}
File file = ESP_FS.open(path.c_str(), "r");
if (!file || file.isDirectory()) {
FILE* file = fopen(path.c_str(), "rb");
if (!file) {
if (sendMetadataCallback_) {
socket_message_FSDownloadMetadata metadata = socket_message_FSDownloadMetadata_init_zero;
metadata.success = false;
@@ -220,11 +237,7 @@ void FileSystemHandler::handleDownloadRequest(const socket_message_FSDownloadReq
return;
}
// Set file buffer size large, so we use ram to read from
// Set buffer size so 1 mb (static) TODO: Check that there is enough ram to do this
file.setBufferSize(1000000);
uint32_t fileSize = file.size();
uint32_t fileSize = st.st_size;
uint32_t chunkSize = FS_MAX_CHUNK_SIZE;
uint32_t totalChunks = (fileSize + chunkSize - 1) / chunkSize;
if (totalChunks == 0) totalChunks = 1;
@@ -254,10 +267,8 @@ void FileSystemHandler::handleDownloadRequest(const socket_message_FSDownloadReq
ESP_LOGI(TAG, "Download started: %s, size=%u, chunks=%u, id=%u", path.c_str(), fileSize, totalChunks, transferId);
// Start streaming chunks immediately
while (sendNextDownloadChunk(transferId)) {
// Keep sending until done or error
taskYIELD(); // Allow other tasks to run
taskYIELD();
}
}
@@ -280,7 +291,7 @@ bool FileSystemHandler::sendNextDownloadChunk(uint32_t transferId) {
sendCompleteCallback_(complete, state.clientId);
}
state.file.close();
fclose(state.file);
downloads_.erase(it);
ESP_LOGI(TAG, "Download completed: %u", transferId);
return false;
@@ -297,7 +308,7 @@ bool FileSystemHandler::sendNextDownloadChunk(uint32_t transferId) {
bytesToRead = state.fileSize - position;
}
size_t bytesRead = state.file.read(data->data.bytes, bytesToRead);
size_t bytesRead = fread(data->data.bytes, 1, bytesToRead, state.file);
if (bytesRead == 0 && bytesToRead > 0) {
delete data;
if (sendCompleteCallback_) {
@@ -310,7 +321,7 @@ bool FileSystemHandler::sendNextDownloadChunk(uint32_t transferId) {
sendCompleteCallback_(complete, state.clientId);
}
state.file.close();
fclose(state.file);
downloads_.erase(it);
ESP_LOGE(TAG, "Download failed - read error: %u", transferId);
return false;
@@ -328,45 +339,40 @@ bool FileSystemHandler::sendNextDownloadChunk(uint32_t transferId) {
return true;
}
// ===== STREAMING UPLOAD =====
socket_message_FSUploadStartResponse FileSystemHandler::handleUploadStart(const socket_message_FSUploadStart& req,
int clientId) {
socket_message_FSUploadStartResponse response = socket_message_FSUploadStartResponse_init_zero;
std::string path(req.path);
std::string path = std::string(MOUNT_POINT) + req.path;
ESP_LOGI(TAG, "Upload start request: %s, size=%u, chunks=%u", path.c_str(), req.file_size, req.total_chunks);
// Check available space
size_t fs_total = 0, fs_used = 0;
esp_littlefs_info("spiffs", &fs_total, &fs_used);
size_t freeSpace = fs_total - fs_used;
if (freeSpace < req.file_size + 4096) { // 4KB safety margin
if (freeSpace < req.file_size + 4096) {
response.success = false;
strncpy(response.error, "Insufficient storage space", sizeof(response.error) - 1);
return response;
}
// Ensure parent directory exists
size_t lastSlash = path.find_last_of('/');
if (lastSlash != std::string::npos && lastSlash > 0) {
std::string parentDir = path.substr(0, lastSlash);
if (!ESP_FS.exists(parentDir.c_str())) {
struct stat st;
if (stat(parentDir.c_str(), &st) != 0) {
response.success = false;
strncpy(response.error, "Parent directory does not exist", sizeof(response.error) - 1);
return response;
}
}
File file = ESP_FS.open(path.c_str(), FILE_WRITE);
FILE* file = fopen(path.c_str(), "wb");
if (!file) {
response.success = false;
strncpy(response.error, "Cannot open file for writing", sizeof(response.error) - 1);
return response;
}
file.setBufferSize(1000000);
uint32_t transferId = generateTransferId();
UploadState state;
@@ -402,20 +408,15 @@ void FileSystemHandler::handleUploadData(const socket_message_FSUploadData& req)
UploadState& state = it->second;
state.lastActivityTime = esp_timer_get_time() / 1000;
// Skip if we already have an error
if (state.hasError) {
return;
}
// Validate chunk index (allow out-of-order but warn)
if (req.chunk_index != state.chunksReceived) {
ESP_LOGW(TAG, "Upload chunk out of order: expected %u, got %u", state.chunksReceived, req.chunk_index);
// For now, we'll accept it anyway and write sequentially
// A more robust implementation would buffer out-of-order chunks
}
// Write chunk data
size_t bytesWritten = state.file.write(req.data.bytes, req.data.size);
size_t bytesWritten = fwrite(req.data.bytes, 1, req.data.size, state.file);
if (bytesWritten != req.data.size) {
state.hasError = true;
state.errorMessage = "Failed to write chunk";
@@ -426,15 +427,13 @@ void FileSystemHandler::handleUploadData(const socket_message_FSUploadData& req)
state.chunksReceived++;
state.bytesReceived += bytesWritten;
// Flush periodically to prevent LittleFS buffer issues
if (state.chunksReceived > 0 && state.chunksReceived % 64 == 0) {
ESP_LOGD(TAG, "Flushing file at chunk %u", state.chunksReceived);
state.file.flush();
fflush(state.file);
}
ESP_LOGD(TAG, "Upload chunk %u/%u: %u bytes", state.chunksReceived, state.totalChunks, bytesWritten);
// Check if upload is complete
if (state.chunksReceived >= state.totalChunks) {
finalizeUpload(transferId, true);
}
@@ -449,11 +448,11 @@ void FileSystemHandler::finalizeUpload(uint32_t transferId, bool success, const
UploadState& state = it->second;
if (state.file) {
state.file.close();
fclose(state.file);
}
if (!success) {
ESP_FS.remove(state.path.c_str());
remove(state.path.c_str());
ESP_LOGW(TAG, "Upload failed, deleted partial file: %s", state.path.c_str());
} else {
ESP_LOGI(TAG, "Upload completed: %s (%u bytes)", state.path.c_str(), state.bytesReceived);
@@ -473,8 +472,6 @@ void FileSystemHandler::finalizeUpload(uint32_t transferId, bool success, const
uploads_.erase(it);
}
// ===== TRANSFER CONTROL =====
socket_message_FSCancelTransferResponse FileSystemHandler::handleCancelTransfer(
const socket_message_FSCancelTransfer& req) {
socket_message_FSCancelTransferResponse response = socket_message_FSCancelTransferResponse_init_zero;
@@ -484,7 +481,7 @@ socket_message_FSCancelTransferResponse FileSystemHandler::handleCancelTransfer(
auto dlIt = downloads_.find(transferId);
if (dlIt != downloads_.end()) {
if (dlIt->second.file) {
dlIt->second.file.close();
fclose(dlIt->second.file);
}
downloads_.erase(dlIt);
response.success = true;
@@ -495,9 +492,9 @@ socket_message_FSCancelTransferResponse FileSystemHandler::handleCancelTransfer(
auto ulIt = uploads_.find(transferId);
if (ulIt != uploads_.end()) {
if (ulIt->second.file) {
ulIt->second.file.close();
fclose(ulIt->second.file);
}
ESP_FS.remove(ulIt->second.path.c_str());
remove(ulIt->second.path.c_str());
uploads_.erase(ulIt);
response.success = true;
ESP_LOGI(TAG, "Upload cancelled: %u", transferId);
@@ -508,4 +505,6 @@ socket_message_FSCancelTransferResponse FileSystemHandler::handleCancelTransfer(
return response;
}
void FileSystemHandler::processPendingDownloads() {}
} // namespace FileSystemWS
+36
View File
@@ -0,0 +1,36 @@
dependencies:
idf:
version: ">=5.0.0"
espressif/mdns:
version: "^1.3.0"
joltwallet/littlefs:
version: "^1.14.0"
espressif/esp-dsp:
version: "^1.4.0"
espressif/led_strip:
version: "^2.5.0"
espressif/esp32-camera:
version: "^2.0.0"
rules:
- if: "idf_version >=5.0.0"
- if: "target not in [esp32p4]"
espressif/esp_wifi_remote:
version: ">=0.3.0"
rules:
- if: "target in [esp32p4]"
espressif/esp_hosted:
version: ">=0.0.6"
rules:
- if: "target in [esp32p4]"
espressif/esp_cam_sensor:
version: ">=0.5.0"
rules:
- if: "target in [esp32p4]"
+90 -64
View File
@@ -1,6 +1,9 @@
#include <Arduino.h>
#include <ESPmDNS.h>
#include <WiFi.h>
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include <esp_log.h>
#include <nvs_flash.h>
#include <wifi/wifi_idf.h>
#include <mdns.h>
#include <map>
#include <filesystem.h>
@@ -18,9 +21,13 @@
#include <mdns_service.h>
#include <system_service.h>
#if CONFIG_IDF_TARGET_ESP32P4
#include <esp_hosted.h>
#endif
#include <www_mount.hpp>
Websocket socket {server, "/api/ws"};
Websocket wsSocket {server, "/api/ws"};
Peripherals peripherals;
ServoController servoController;
@@ -39,7 +46,7 @@ WiFiService wifiService;
APService apService;
void setupServer() {
server.config(50 + WWW_ASSETS_COUNT, 32768);
server.config(50 + WWW_ASSETS_COUNT, 16384);
server.listen(80);
server.on("/api/system/reset", HTTP_POST,
@@ -52,11 +59,13 @@ void setupServer() {
server.on("/api/camera/still", HTTP_GET, [&](httpd_req_t *request) { return cameraService.cameraStill(request); });
server.on("/api/camera/stream", HTTP_GET,
[&](httpd_req_t *request) { return cameraService.cameraStream(request); });
#if USE_DVP_CAMERA
server.on("/api/camera/settings", HTTP_GET,
[&](httpd_req_t *request) { return cameraService.protoEndpoint.getState(request); });
server.on("/api/camera/settings", HTTP_POST, [&](httpd_req_t *request, api_Request *protoReq) {
return cameraService.protoEndpoint.handleStateUpdate(request, protoReq);
});
#endif
#endif
server.on("/api/servo/config", HTTP_GET,
[&](httpd_req_t *request) { return servoController.protoEndpoint.getState(request); });
@@ -73,42 +82,41 @@ void setupServer() {
server.on("/api/wifi/networks", HTTP_GET, [&](httpd_req_t *request) { return wifiService.getNetworks(request); });
server.on("/api/wifi/sta/status", HTTP_GET,
[&](httpd_req_t *request) { return wifiService.getNetworkStatus(request); });
server.on("/api/ap/status", HTTP_GET, [&](httpd_req_t *request) { return apService.getStatusProto(request); });
server.on("/api/ap/settings", HTTP_GET,
[&](httpd_req_t *request) { return apService.protoEndpoint.getState(request); });
server.on("/api/ap/settings", HTTP_POST,
[&](httpd_req_t *request, api_Request *protoReq) {
return apService.protoEndpoint.handleStateUpdate(request, protoReq);
});
[&](httpd_req_t *request) { return apService.protoEndpoint.getState(request); });
server.on("/api/ap/settings", HTTP_POST, [&](httpd_req_t *request, api_Request *protoReq) {
return apService.protoEndpoint.handleStateUpdate(request, protoReq);
});
server.on("/api/peripherals/settings", HTTP_GET,
[&](httpd_req_t *request) { return peripherals.protoEndpoint.getState(request); });
server.on("/api/peripherals/settings", HTTP_POST,
[&](httpd_req_t *request, api_Request *protoReq) {
return peripherals.protoEndpoint.handleStateUpdate(request, protoReq);
});
server.on("/api/peripherals/settings", HTTP_POST, [&](httpd_req_t *request, api_Request *protoReq) {
return peripherals.protoEndpoint.handleStateUpdate(request, protoReq);
});
#if FT_ENABLED(USE_MDNS)
server.on("/api/mdns/settings", HTTP_GET, [&](httpd_req_t *request) { return mdnsService.protoEndpoint.getState(request); });
server.on("/api/mdns/settings", HTTP_POST,
[&](httpd_req_t *request, api_Request *protoReq) {
return mdnsService.protoEndpoint.handleStateUpdate(request, protoReq);
});
server.on("/api/mdns/settings", HTTP_GET,
[&](httpd_req_t *request) { return mdnsService.protoEndpoint.getState(request); });
server.on("/api/mdns/settings", HTTP_POST, [&](httpd_req_t *request, api_Request *protoReq) {
return mdnsService.protoEndpoint.handleStateUpdate(request, protoReq);
});
server.on("/api/mdns/status", HTTP_GET, [&](httpd_req_t *request) { return mdnsService.getStatus(request); });
server.on("/api/mdns/query", HTTP_POST,
[&](httpd_req_t *request, api_Request *protoReq) {
return mdnsService.queryServices(request, protoReq);
});
server.on("/api/mdns/query", HTTP_POST, [&](httpd_req_t *request, api_Request *protoReq) {
return mdnsService.queryServices(request, protoReq);
});
#endif
server.on("/api/config/*", HTTP_GET, [](httpd_req_t *request) { return FileSystem::getConfigFile(request); });
server.on("/api/files", HTTP_GET, [&](httpd_req_t *request) { return FileSystem::getFilesProto(request); });
STAITC_PROTO_POST_ENDPOINT(server, "/api/files/delete", file_delete_request, FileSystem::handleDelete);
STAITC_PROTO_POST_ENDPOINT(server, "/api/files/edit", file_edit_request, FileSystem::handleEdit);
STAITC_PROTO_POST_ENDPOINT(server, "/api/files/mkdir", file_mkdir_request, FileSystem::mkdir);
wsSocket.begin();
#if EMBED_WEBAPP
mountStaticAssets(server);
mountSpaFallback(server);
#endif
server.on("/*", HTTP_OPTIONS, [](httpd_req_t *request) {
httpd_resp_set_status(request, "200 OK");
@@ -123,35 +131,35 @@ void setupServer() {
void setupEventSocket() {
FileSystemWS::fsHandler.setSendCallbacks(
[](const socket_message_FSDownloadMetadata &metadata, int clientId) { socket.emit(metadata, clientId); },
[](const socket_message_FSDownloadData &data, int clientId) { socket.emit(data, clientId); },
[](const socket_message_FSDownloadComplete &complete, int clientId) { socket.emit(complete, clientId); },
[](const socket_message_FSUploadComplete &complete, int clientId) { socket.emit(complete, clientId); });
[](const socket_message_FSDownloadMetadata &metadata, int clientId) { wsSocket.emit(metadata, clientId); },
[](const socket_message_FSDownloadData &data, int clientId) { wsSocket.emit(data, clientId); },
[](const socket_message_FSDownloadComplete &complete, int clientId) { wsSocket.emit(complete, clientId); },
[](const socket_message_FSUploadComplete &complete, int clientId) { wsSocket.emit(complete, clientId); });
socket.on<socket_message_ControllerData>(
wsSocket.on<socket_message_ControllerData>(
[&](const socket_message_ControllerData &data, int clientId) { motionService.handleInput(data); });
socket.on<socket_message_ModeData>([&](const socket_message_ModeData &data, int clientId) {
wsSocket.on<socket_message_ModeData>([&](const socket_message_ModeData &data, int clientId) {
servoController.setMode(SERVO_CONTROL_STATE::ANGLE);
motionService.handleMode(data);
motionService.isActive() ? servoController.activate() : servoController.deactivate();
});
socket.on<socket_message_WalkGaitData>(
wsSocket.on<socket_message_WalkGaitData>(
[&](const socket_message_WalkGaitData &data, int clientId) { motionService.handleWalkGait(data); });
socket.on<socket_message_AnglesData>(
wsSocket.on<socket_message_AnglesData>(
[&](const socket_message_AnglesData &data, int clientId) { motionService.handleAngles(data); });
socket.on<socket_message_ServoPWMData>([&](const socket_message_ServoPWMData &data, int clientId) {
wsSocket.on<socket_message_ServoPWMData>([&](const socket_message_ServoPWMData &data, int clientId) {
servoController.setServoPWM(data.servo_id, data.servo_pwm);
});
socket.on<socket_message_ServoStateData>([&](const socket_message_ServoStateData &data, int clientId) {
wsSocket.on<socket_message_ServoStateData>([&](const socket_message_ServoStateData &data, int clientId) {
data.active ? servoController.activate() : servoController.deactivate();
});
socket.on<socket_message_FSUploadData>(
wsSocket.on<socket_message_FSUploadData>(
[&](const socket_message_FSUploadData &data, int clientId) { FileSystemWS::fsHandler.handleUploadData(data); });
using CorrelationHandler =
@@ -225,7 +233,7 @@ void setupEventSocket() {
}},
};
socket.on<socket_message_CorrelationRequest>([&](const socket_message_CorrelationRequest &data, int clientId) {
wsSocket.on<socket_message_CorrelationRequest>([&](const socket_message_CorrelationRequest &data, int clientId) {
auto res = new socket_message_CorrelationResponse();
*res = socket_message_CorrelationResponse_init_default;
res->correlation_id = data.correlation_id;
@@ -235,7 +243,7 @@ void setupEventSocket() {
if (it != correlationHandlers.end()) {
it->second(data, *res, clientId);
if (res->status_code != 0) {
socket.emit(*res, clientId);
wsSocket.emit(*res, clientId);
}
} else {
printf("WARNING: no handler for correlation request: %d\n", data.which_request);
@@ -248,15 +256,18 @@ void setupEventSocket() {
void IRAM_ATTR SpotControlLoopEntry(void *) {
ESP_LOGI("main", "Control task starting");
TickType_t xLastWakeTime = xTaskGetTickCount();
const TickType_t xFrequency = 5 / portTICK_PERIOD_MS;
const TickType_t xFrequency = pdMS_TO_TICKS(10);
peripherals.begin();
servoController.begin();
motionService.begin();
#if FT_ENABLED(USE_WS2812)
ledService.begin();
#endif
peripherals.calibrateIMU();
for (;;) {
WARN_IF_SLOW(SpotControlLoopEntry, 5);
WARN_IF_SLOW(SpotControlLoopEntry, 10);
peripherals.update();
motionService.update(&peripherals);
servoController.setAngles(motionService.getAngles());
@@ -264,22 +275,33 @@ void IRAM_ATTR SpotControlLoopEntry(void *) {
#if FT_ENABLED(USE_WS2812)
ledService.loop();
#endif
// CALLS_PER_SECOND_TIMED(SpotControlLoopEntry,
// CALLS_PER_SECOND_TIMED_FUNC_PRINT(SpotControlLoopEntry, peripherals_update)
// CALLS_PER_SECOND_TIMED_FUNC_PRINT(SpotControlLoopEntry, motionService_update)
// CALLS_PER_SECOND_TIMED_FUNC_PRINT(SpotControlLoopEntry, servoController_setAngles)
// CALLS_PER_SECOND_TIMED_FUNC_PRINT(SpotControlLoopEntry, servoController_update)
// );
// vTaskDelayUntil(&xLastWakeTime, xFrequency);
vTaskDelayUntil(&xLastWakeTime, xFrequency);
}
}
void IRAM_ATTR serviceLoopEntry(void *) {
ESP_LOGI("main", "Service task starting");
#if CONFIG_IDF_TARGET_ESP32P4
ESP_LOGI("main", "Initializing ESP-Hosted for C6 coprocessor WiFi...");
int ret = esp_hosted_init();
if (ret != 0) {
ESP_LOGE("main", "ESP-Hosted init failed: %d", ret);
} else {
ESP_LOGI("main", "ESP-Hosted initialized, connecting to C6...");
ret = esp_hosted_connect_to_slave();
if (ret != 0) {
ESP_LOGW("main", "ESP-Hosted connect failed: %d - WiFi may not work", ret);
} else {
ESP_LOGI("main", "ESP-Hosted link established with C6");
}
}
#endif
WiFi.init();
wifiService.begin();
MDNS.begin(APP_NAME);
MDNS.setInstanceName(APP_NAME);
mdns_init();
mdns_hostname_set(APP_NAME);
mdns_instance_name_set(APP_NAME);
apService.begin();
#if FT_ENABLED(USE_CAMERA)
@@ -287,33 +309,32 @@ void IRAM_ATTR serviceLoopEntry(void *) {
#endif
setupServer();
socket.begin();
setupEventSocket();
ESP_LOGI("main", "Service task started");
for (;;) {
wifiService.loop();
apService.loop();
EXECUTE_EVERY_N_MS(2000, {
if (socket.hasSubscribers(socket_message_Message_analytics_tag)) {
if (wsSocket.hasSubscribers(socket_message_Message_analytics_tag)) {
socket_message_AnalyticsData analytics = socket_message_AnalyticsData_init_zero;
system_service::getAnalytics(analytics);
socket.emit(analytics);
wsSocket.emit(analytics);
}
});
EXECUTE_EVERY_N_MS(100, {
if (socket.hasSubscribers(socket_message_Message_imu_tag)) {
if (wsSocket.hasSubscribers(socket_message_Message_imu_tag)) {
socket_message_IMUData imu = socket_message_IMUData_init_zero;
peripherals.getIMUProto(imu);
socket.emit(imu);
wsSocket.emit(imu);
}
if (socket.hasSubscribers(socket_message_Message_rssi_tag)) {
if (wsSocket.hasSubscribers(socket_message_Message_rssi_tag)) {
socket_message_RSSIData rssi = {.rssi = WiFi.RSSI()};
socket.emit(rssi);
wsSocket.emit(rssi);
}
});
@@ -323,18 +344,23 @@ void IRAM_ATTR serviceLoopEntry(void *) {
}
}
void setup() {
ESP_FS.begin();
extern "C" void app_main(void) {
esp_err_t ret = nvs_flash_init();
if (ret == ESP_ERR_NVS_NO_FREE_PAGES || ret == ESP_ERR_NVS_NEW_VERSION_FOUND) {
ESP_ERROR_CHECK(nvs_flash_erase());
ret = nvs_flash_init();
}
ESP_ERROR_CHECK(ret);
FileSystem::init();
ESP_LOGI("main", "Booting robot");
feature_service::printFeatureConfiguration();
xTaskCreate(serviceLoopEntry, "Service task", 4096, nullptr, 2, nullptr);
xTaskCreate(serviceLoopEntry, "Service task", 8192, nullptr, 2, nullptr);
xTaskCreatePinnedToCore(SpotControlLoopEntry, "Control task", 4096, nullptr, 5, nullptr, 1);
xTaskCreatePinnedToCore(SpotControlLoopEntry, "Control task", 8192, nullptr, 5, nullptr, 1);
ESP_LOGI("main", "Finished booting");
}
void loop() { vTaskDelete(nullptr); }
+67 -26
View File
@@ -1,5 +1,6 @@
#include <mdns_service.h>
#include <communication/webserver.h>
#include <esp_netif.h>
static const char *TAG = "MDNSService";
@@ -7,9 +8,8 @@ MDNSService::MDNSService()
: protoEndpoint(MDNSSettings_read, MDNSSettings_update, this,
API_REQUEST_EXTRACTOR(mdns_settings, api_MDNSSettings),
API_RESPONSE_ASSIGNER(mdns_settings, api_MDNSSettings)),
_persistence(MDNSSettings_read, MDNSSettings_update, this,
MDNS_SETTINGS_FILE, api_MDNSSettings_fields, api_MDNSSettings_size,
MDNSSettings_defaults()) {
_persistence(MDNSSettings_read, MDNSSettings_update, this, MDNS_SETTINGS_FILE, api_MDNSSettings_fields,
api_MDNSSettings_size, MDNSSettings_defaults()) {
addUpdateHandler([&](const std::string &originId) { reconfigureMDNS(); }, false);
}
@@ -34,33 +34,50 @@ void MDNSService::reconfigureMDNS() {
void MDNSService::startMDNS() {
ESP_LOGV(TAG, "Starting MDNS with hostname: %s", state().hostname);
if (MDNS.begin(state().hostname)) {
_started = true;
MDNS.setInstanceName(state().instance);
addServices();
ESP_LOGI(TAG, "MDNS started successfully with hostname: %s", state().hostname);
} else {
esp_err_t err = mdns_init();
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to initialize MDNS: %s", esp_err_to_name(err));
_started = false;
ESP_LOGE(TAG, "Failed to start MDNS");
return;
}
err = mdns_hostname_set(state().hostname);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to set MDNS hostname: %s", esp_err_to_name(err));
mdns_free();
_started = false;
return;
}
err = mdns_instance_name_set(state().instance);
if (err != ESP_OK) {
ESP_LOGW(TAG, "Failed to set MDNS instance name: %s", esp_err_to_name(err));
}
_started = true;
addServices();
ESP_LOGI(TAG, "MDNS started successfully with hostname: %s", state().hostname);
}
void MDNSService::stopMDNS() {
ESP_LOGV(TAG, "Stopping MDNS");
MDNS.end();
mdns_free();
_started = false;
}
void MDNSService::addServices() {
for (size_t i = 0; i < state().services_count; i++) {
const auto &service = state().services[i];
MDNS.addService(service.service, service.protocol, service.port);
esp_err_t err = mdns_service_add(nullptr, service.service, service.protocol, service.port, nullptr, 0);
if (err != ESP_OK) {
ESP_LOGW(TAG, "Failed to add service %s: %s", service.service, esp_err_to_name(err));
continue;
}
for (size_t j = 0; j < service.txt_records_count; j++) {
const auto &txt = service.txt_records[j];
MDNS.addServiceTxt(service.service, service.protocol, txt.key, txt.value);
mdns_service_txt_item_set(service.service, service.protocol, txt.key, txt.value);
}
}
@@ -68,7 +85,7 @@ void MDNSService::addServices() {
const auto &txt = state().global_txt_records[i];
for (size_t j = 0; j < state().services_count; j++) {
const auto &service = state().services[j];
MDNS.addServiceTxt(service.service, service.protocol, txt.key, txt.value);
mdns_service_txt_item_set(service.service, service.protocol, txt.key, txt.value);
}
}
}
@@ -103,22 +120,46 @@ esp_err_t MDNSService::queryServices(httpd_req_t *request, api_Request *protoReq
const api_MDNSQueryRequest &queryReq = protoReq->payload.mdns_query_request;
ESP_LOGI(TAG, "Querying for service: %s, protocol: %s", queryReq.service, queryReq.protocol);
int n = MDNS.queryService(queryReq.service, queryReq.protocol);
ESP_LOGI(TAG, "Found %d services", n);
mdns_result_t *results = nullptr;
esp_err_t err = mdns_query_ptr(queryReq.service, queryReq.protocol, 3000, 20, &results);
api_Response response = api_Response_init_zero;
response.which_payload = api_Response_mdns_query_response_tag;
api_MDNSQueryResponse &queryResp = response.payload.mdns_query_response;
// Limit to max_count from options file (16)
size_t count = (n > 16) ? 16 : static_cast<size_t>(n);
queryResp.services_count = count;
for (size_t i = 0; i < count; i++) {
strncpy(queryResp.services[i].name, MDNS.hostname(i).c_str(), sizeof(queryResp.services[i].name) - 1);
strncpy(queryResp.services[i].ip, MDNS.IP(i).toString().c_str(), sizeof(queryResp.services[i].ip) - 1);
queryResp.services[i].port = MDNS.port(i);
if (err != ESP_OK) {
ESP_LOGW(TAG, "MDNS query failed: %s", esp_err_to_name(err));
queryResp.services_count = 0;
return WebServer::send(request, 200, response, api_Response_fields);
}
int count = 0;
mdns_result_t *r = results;
while (r && count < 16) {
count++;
r = r->next;
}
ESP_LOGI(TAG, "Found %d services", count);
queryResp.services_count = count;
r = results;
size_t i = 0;
while (r && i < 16) {
if (r->hostname) {
strncpy(queryResp.services[i].name, r->hostname, sizeof(queryResp.services[i].name) - 1);
}
if (r->addr) {
char ip_str[16];
esp_ip4addr_ntoa(&r->addr->addr.u_addr.ip4, ip_str, sizeof(ip_str));
strncpy(queryResp.services[i].ip, ip_str, sizeof(queryResp.services[i].ip) - 1);
}
queryResp.services[i].port = r->port;
r = r->next;
i++;
}
mdns_query_results_free(results);
return WebServer::send(request, 200, response, api_Response_fields);
}
+468 -7
View File
@@ -1,13 +1,18 @@
#include <peripherals/camera_service.h>
#include <communication/webserver.h>
#include <esp_heap_caps.h>
namespace Camera {
static const char *const TAG = "CameraService";
#if USE_DVP_CAMERA || USE_CSI_CAMERA
static constexpr const char *_STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static constexpr const char *_STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static constexpr const char *_STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
#endif
#if USE_DVP_CAMERA
SemaphoreHandle_t cameraMutex = xSemaphoreCreateMutex();
@@ -34,9 +39,8 @@ CameraService::CameraService()
: protoEndpoint(CameraSettings_read, CameraSettings_update, this,
API_REQUEST_EXTRACTOR(camera_settings, api_CameraSettings),
API_RESPONSE_ASSIGNER(camera_settings, api_CameraSettings)),
_persistence(CameraSettings_read, CameraSettings_update, this,
CAMERA_SETTINGS_FILE, api_CameraSettings_fields, api_CameraSettings_size,
CameraSettings_defaults()) {
_persistence(CameraSettings_read, CameraSettings_update, this, CAMERA_SETTINGS_FILE, api_CameraSettings_fields,
api_CameraSettings_size, CameraSettings_defaults()) {
addUpdateHandler([&](const std::string &originId) { updateCamera(); }, false);
}
@@ -45,7 +49,6 @@ esp_err_t CameraService::begin() {
camera_config_t camera_config;
camera_config.ledc_channel = LEDC_CHANNEL_0;
camera_config.ledc_timer = LEDC_TIMER_0;
#if FT_ENABLED(USE_CAMERA)
camera_config.pin_d0 = Y2_GPIO_NUM;
camera_config.pin_d1 = Y3_GPIO_NUM;
camera_config.pin_d2 = Y4_GPIO_NUM;
@@ -62,11 +65,10 @@ esp_err_t CameraService::begin() {
camera_config.pin_sccb_scl = SIOC_GPIO_NUM;
camera_config.pin_pwdn = PWDN_GPIO_NUM;
camera_config.pin_reset = RESET_GPIO_NUM;
#endif
camera_config.xclk_freq_hz = 20000000;
camera_config.pixel_format = PIXFORMAT_JPEG;
if (psramFound()) {
if (heap_caps_get_total_size(MALLOC_CAP_SPIRAM) > 0) {
camera_config.frame_size = FRAMESIZE_SVGA;
camera_config.jpeg_quality = 10;
camera_config.fb_location = CAMERA_FB_IN_PSRAM;
@@ -78,7 +80,7 @@ esp_err_t CameraService::begin() {
camera_config.fb_count = 1;
}
log_i("Initializing camera");
ESP_LOGI(TAG, "Initializing camera");
esp_err_t err = esp_camera_init(&camera_config);
if (err == ESP_OK)
ESP_LOGI(TAG, "Camera probe successful");
@@ -180,4 +182,463 @@ void CameraService::updateCamera() {
safe_sensor_return();
}
#elif USE_CSI_CAMERA
}
extern "C" {
#include "esp_cam_ctlr.h"
#include "esp_cam_ctlr_csi.h"
#include "esp_cam_ctlr_types.h"
#include "driver/isp.h"
#include "driver/jpeg_encode.h"
#include "esp_sccb_intf.h"
#include "esp_sccb_i2c.h"
#include "esp_cam_sensor.h"
#include "ov5647.h"
#include "esp_ldo_regulator.h"
#include "driver/isp_demosaic.h"
#include "driver/isp_bf.h"
#include "driver/isp_sharpen.h"
}
#include <peripherals/i2c_bus.h>
namespace Camera {
#ifndef MIPI_CSI_HRES
#define MIPI_CSI_HRES 640
#endif
#ifndef MIPI_CSI_VRES
#define MIPI_CSI_VRES 480
#endif
#ifndef MIPI_CSI_LANE_BITRATE_MBPS
#define MIPI_CSI_LANE_BITRATE_MBPS 200
#endif
#ifndef MIPI_CSI_DATA_LANES
#define MIPI_CSI_DATA_LANES 2
#endif
#ifndef CAM_SCCB_FREQ_HZ
#define CAM_SCCB_FREQ_HZ 100000
#endif
#ifndef CAM_SENSOR_ADDR
#define CAM_SENSOR_ADDR 0x36
#endif
#ifndef CAM_XCLK_PIN
#define CAM_XCLK_PIN -1
#endif
#ifndef CAM_XCLK_FREQ_HZ
#define CAM_XCLK_FREQ_HZ 25000000
#endif
#ifndef CAM_RESET_PIN
#define CAM_RESET_PIN -1
#endif
#ifndef CAM_PWDN_PIN
#define CAM_PWDN_PIN -1
#endif
#ifndef CSI_JPEG_QUALITY
#define CSI_JPEG_QUALITY 80
#endif
#define NUM_FRAME_BUFS 2
static constexpr size_t CACHE_LINE_SIZE = 64;
#define ALIGN_UP(n, a) (((n) + ((a) - 1)) & ~((a) - 1))
static esp_cam_ctlr_handle_t s_cam_handle = NULL;
static isp_proc_handle_t s_isp_proc = NULL;
static jpeg_encoder_handle_t s_jpeg_enc = NULL;
static uint8_t *s_frame_bufs[NUM_FRAME_BUFS] = {};
static size_t s_frame_buf_size = 0;
static uint8_t *s_jpeg_bufs[NUM_FRAME_BUFS] = {};
static size_t s_jpeg_buf_alloc = 0;
static bool s_cam_initialized = false;
static uint16_t s_frame_hres = MIPI_CSI_HRES;
static uint16_t s_frame_vres = MIPI_CSI_VRES;
static SemaphoreHandle_t s_frame_done = NULL;
static SemaphoreHandle_t s_jpeg_lock = NULL;
static SemaphoreHandle_t s_jpeg_ready = NULL;
static TaskHandle_t s_capture_task = NULL;
static volatile bool s_capture_running = false;
static int s_write_idx = 0;
static int s_ready_idx = -1;
static size_t s_ready_jpeg_len = 0;
static uint8_t *s_send_buf = NULL;
static size_t s_send_buf_size = 0;
static bool on_trans_finished(esp_cam_ctlr_handle_t handle, esp_cam_ctlr_trans_t *trans, void *user_data) {
BaseType_t woken = pdFALSE;
xSemaphoreGiveFromISR(s_frame_done, &woken);
return (woken == pdTRUE);
}
static void capture_task_fn(void *arg) {
while (s_capture_running) {
int idx = s_write_idx;
esp_cam_ctlr_trans_t trans = {};
trans.buffer = s_frame_bufs[idx];
trans.buflen = s_frame_buf_size;
if (esp_cam_ctlr_receive(s_cam_handle, &trans, 2000) != ESP_OK) {
vTaskDelay(pdMS_TO_TICKS(5));
continue;
}
if (xSemaphoreTake(s_frame_done, pdMS_TO_TICKS(2000)) != pdTRUE) {
continue;
}
jpeg_encode_cfg_t enc_cfg = {};
enc_cfg.src_type = JPEG_ENCODE_IN_FORMAT_RGB565;
enc_cfg.sub_sample = JPEG_DOWN_SAMPLING_YUV420;
enc_cfg.image_quality = CSI_JPEG_QUALITY;
enc_cfg.width = s_frame_hres;
enc_cfg.height = s_frame_vres;
uint32_t out_size = 0;
esp_err_t err = jpeg_encoder_process(s_jpeg_enc, &enc_cfg, s_frame_bufs[idx], trans.received_size,
s_jpeg_bufs[idx], s_jpeg_buf_alloc, &out_size);
if (err != ESP_OK) {
continue;
}
xSemaphoreTake(s_jpeg_lock, portMAX_DELAY);
s_ready_idx = idx;
s_ready_jpeg_len = out_size;
xSemaphoreGive(s_jpeg_lock);
s_write_idx = (idx + 1) % NUM_FRAME_BUFS;
xSemaphoreGive(s_jpeg_ready);
}
vTaskDelete(NULL);
}
CameraService::CameraService() {
s_frame_done = xSemaphoreCreateBinary();
s_jpeg_lock = xSemaphoreCreateMutex();
s_jpeg_ready = xSemaphoreCreateBinary();
}
esp_err_t CameraService::begin() {
ESP_LOGI(TAG, "Initializing MIPI-CSI camera for ESP32-P4");
esp_ldo_channel_handle_t ldo_mipi_phy = NULL;
esp_ldo_channel_config_t ldo_cfg = {};
ldo_cfg.chan_id = 3;
ldo_cfg.voltage_mv = 2500;
esp_err_t ldo_err = esp_ldo_acquire_channel(&ldo_cfg, &ldo_mipi_phy);
if (ldo_err != ESP_OK) {
ESP_LOGE(TAG, "Failed to acquire MIPI PHY LDO: %s", esp_err_to_name(ldo_err));
return ldo_err;
}
i2c_master_bus_handle_t i2c_bus = I2CBus::instance().busHandle();
if (!i2c_bus) {
ESP_LOGE(TAG, "I2C bus not initialized, cannot init camera SCCB");
return ESP_ERR_INVALID_STATE;
}
esp_sccb_io_handle_t sccb_io = NULL;
sccb_i2c_config_t sccb_cfg = {};
sccb_cfg.scl_speed_hz = CAM_SCCB_FREQ_HZ;
sccb_cfg.device_address = CAM_SENSOR_ADDR;
sccb_cfg.dev_addr_length = I2C_ADDR_BIT_LEN_7;
esp_err_t err = sccb_new_i2c_io(i2c_bus, &sccb_cfg, &sccb_io);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to create SCCB I/O handle: %s", esp_err_to_name(err));
return err;
}
esp_cam_sensor_config_t cam_sensor_cfg = {};
cam_sensor_cfg.sccb_handle = sccb_io;
cam_sensor_cfg.reset_pin = static_cast<gpio_num_t>(CAM_RESET_PIN);
cam_sensor_cfg.pwdn_pin = static_cast<gpio_num_t>(CAM_PWDN_PIN);
cam_sensor_cfg.xclk_pin = static_cast<gpio_num_t>(CAM_XCLK_PIN);
cam_sensor_cfg.xclk_freq_hz = CAM_XCLK_FREQ_HZ;
cam_sensor_cfg.sensor_port = ESP_CAM_SENSOR_MIPI_CSI;
esp_cam_sensor_device_t *cam_sensor = ov5647_detect(&cam_sensor_cfg);
if (!cam_sensor) {
ESP_LOGE(TAG, "OV5647 detection failed");
return ESP_FAIL;
}
ESP_LOGI(TAG, "OV5647 camera sensor detected");
esp_cam_sensor_format_array_t fmt_array = {};
err = esp_cam_sensor_query_format(cam_sensor, &fmt_array);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to query sensor formats: %s", esp_err_to_name(err));
return err;
}
const esp_cam_sensor_format_t *selected_format = NULL;
uint32_t best_area = 0;
for (uint32_t i = 0; i < fmt_array.count; i++) {
const auto &f = fmt_array.format_array[i];
ESP_LOGI(TAG, "Sensor format[%u]: %dx%d mipi_clk=%uHz lanes=%d", (unsigned)i, f.width, f.height,
(unsigned)f.mipi_info.mipi_clk, f.mipi_info.lane_num);
}
for (uint32_t i = 0; i < fmt_array.count; i++) {
const uint16_t w = fmt_array.format_array[i].width;
const uint16_t h = fmt_array.format_array[i].height;
if (w <= MIPI_CSI_HRES && h <= MIPI_CSI_VRES) {
const uint32_t area = (uint32_t)w * (uint32_t)h;
if (!selected_format || area > best_area) {
selected_format = &fmt_array.format_array[i];
best_area = area;
}
}
}
if (!selected_format && fmt_array.count > 0) {
uint32_t min_area = UINT32_MAX;
for (uint32_t i = 0; i < fmt_array.count; i++) {
const uint32_t area =
(uint32_t)fmt_array.format_array[i].width * (uint32_t)fmt_array.format_array[i].height;
if (area < min_area) {
selected_format = &fmt_array.format_array[i];
min_area = area;
}
}
}
if (!selected_format) {
ESP_LOGE(TAG, "No sensor formats available");
return ESP_FAIL;
}
err = esp_cam_sensor_set_format(cam_sensor, selected_format);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to set sensor format: %s", esp_err_to_name(err));
return err;
}
s_frame_hres = selected_format->width;
s_frame_vres = selected_format->height;
ESP_LOGI(TAG, "Sensor format set: %dx%d", s_frame_hres, s_frame_vres);
esp_cam_sensor_format_t cur_fmt = {};
if (esp_cam_sensor_get_format(cam_sensor, &cur_fmt) == ESP_OK) {
ESP_LOGI(TAG, "Active format: %dx%d, mipi_clk=%uHz, lanes=%d", cur_fmt.width, cur_fmt.height,
(unsigned)cur_fmt.mipi_info.mipi_clk, cur_fmt.mipi_info.lane_num);
}
int stream_on = 1;
err = esp_cam_sensor_ioctl(cam_sensor, ESP_CAM_SENSOR_IOC_S_STREAM, &stream_on);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to start sensor stream: %s", esp_err_to_name(err));
return err;
}
esp_isp_processor_cfg_t isp_cfg = {};
isp_cfg.clk_src = static_cast<isp_clk_src_t>(0);
isp_cfg.clk_hz = 80 * 1000 * 1000;
isp_cfg.input_data_source = ISP_INPUT_DATA_SOURCE_CSI;
isp_cfg.input_data_color_type = ISP_COLOR_RAW8;
isp_cfg.output_data_color_type = ISP_COLOR_RGB565;
isp_cfg.has_line_start_packet = false;
isp_cfg.has_line_end_packet = false;
isp_cfg.h_res = s_frame_hres;
isp_cfg.v_res = s_frame_vres;
isp_cfg.bayer_order = COLOR_RAW_ELEMENT_ORDER_GBRG;
err = esp_isp_new_processor(&isp_cfg, &s_isp_proc);
if (err != ESP_OK) {
ESP_LOGE(TAG, "ISP processor init failed: %s", esp_err_to_name(err));
return err;
}
err = esp_isp_enable(s_isp_proc);
if (err != ESP_OK) {
ESP_LOGE(TAG, "ISP enable failed: %s", esp_err_to_name(err));
return err;
}
esp_isp_demosaic_config_t demosaic_cfg = {};
demosaic_cfg.grad_ratio.val = 16;
demosaic_cfg.padding_mode = ISP_DEMOSAIC_EDGE_PADDING_MODE_SRND_DATA;
esp_isp_demosaic_configure(s_isp_proc, &demosaic_cfg);
esp_isp_demosaic_enable(s_isp_proc);
esp_isp_bf_config_t bf_cfg = {};
bf_cfg.denoising_level = 10;
bf_cfg.padding_mode = ISP_BF_EDGE_PADDING_MODE_SRND_DATA;
uint8_t bf_tpl[ISP_BF_TEMPLATE_X_NUMS][ISP_BF_TEMPLATE_Y_NUMS] = {{1, 2, 1}, {2, 4, 2}, {1, 2, 1}};
memcpy(bf_cfg.bf_template, bf_tpl, sizeof(bf_tpl));
esp_isp_bf_configure(s_isp_proc, &bf_cfg);
esp_isp_bf_enable(s_isp_proc);
esp_isp_sharpen_config_t sharp_cfg = {};
sharp_cfg.h_thresh = 255;
sharp_cfg.l_thresh = 20;
sharp_cfg.padding_mode = ISP_SHARPEN_EDGE_PADDING_MODE_SRND_DATA;
uint8_t sharp_m[ISP_SHARPEN_TEMPLATE_X_NUMS][ISP_SHARPEN_TEMPLATE_Y_NUMS] = {{1, 2, 1}, {2, 4, 2}, {1, 2, 1}};
memcpy(sharp_cfg.sharpen_template, sharp_m, sizeof(sharp_m));
sharp_cfg.h_freq_coeff.integer = 1;
sharp_cfg.h_freq_coeff.decimal = 0;
sharp_cfg.m_freq_coeff.integer = 1;
sharp_cfg.m_freq_coeff.decimal = 0;
esp_isp_sharpen_configure(s_isp_proc, &sharp_cfg);
esp_isp_sharpen_enable(s_isp_proc);
esp_cam_ctlr_csi_config_t csi_cfg = {};
csi_cfg.ctlr_id = 0;
csi_cfg.h_res = s_frame_hres;
csi_cfg.v_res = s_frame_vres;
csi_cfg.lane_bit_rate_mbps = MIPI_CSI_LANE_BITRATE_MBPS;
csi_cfg.input_data_color_type = CAM_CTLR_COLOR_RAW8;
csi_cfg.output_data_color_type = CAM_CTLR_COLOR_RGB565;
csi_cfg.data_lane_num = MIPI_CSI_DATA_LANES;
csi_cfg.byte_swap_en = false;
csi_cfg.queue_items = NUM_FRAME_BUFS;
err = esp_cam_new_csi_ctlr(&csi_cfg, &s_cam_handle);
if (err != ESP_OK) {
ESP_LOGE(TAG, "CSI controller init failed: %s", esp_err_to_name(err));
return err;
}
esp_cam_ctlr_evt_cbs_t cbs = {};
cbs.on_trans_finished = on_trans_finished;
err = esp_cam_ctlr_register_event_callbacks(s_cam_handle, &cbs, NULL);
if (err != ESP_OK) {
ESP_LOGE(TAG, "CSI register callbacks failed: %s", esp_err_to_name(err));
return err;
}
s_frame_buf_size = ALIGN_UP((size_t)s_frame_hres * s_frame_vres * 2, CACHE_LINE_SIZE);
for (int i = 0; i < NUM_FRAME_BUFS; i++) {
s_frame_bufs[i] = (uint8_t *)heap_caps_aligned_alloc(CACHE_LINE_SIZE, s_frame_buf_size, MALLOC_CAP_SPIRAM);
if (!s_frame_bufs[i]) {
ESP_LOGE(TAG, "Failed to allocate frame buffer %d (%d bytes)", i, (int)s_frame_buf_size);
return ESP_ERR_NO_MEM;
}
}
jpeg_encode_memory_alloc_cfg_t jpeg_mem_cfg = {};
jpeg_mem_cfg.buffer_direction = JPEG_ENC_ALLOC_OUTPUT_BUFFER;
for (int i = 0; i < NUM_FRAME_BUFS; i++) {
size_t alloc_sz = 0;
s_jpeg_bufs[i] = (uint8_t *)jpeg_alloc_encoder_mem(s_frame_hres * s_frame_vres, &jpeg_mem_cfg, &alloc_sz);
if (!s_jpeg_bufs[i]) {
ESP_LOGE(TAG, "Failed to allocate JPEG buffer %d", i);
return ESP_ERR_NO_MEM;
}
if (i == 0) s_jpeg_buf_alloc = alloc_sz;
}
s_send_buf_size = s_jpeg_buf_alloc;
s_send_buf = (uint8_t *)heap_caps_aligned_alloc(CACHE_LINE_SIZE, s_send_buf_size, MALLOC_CAP_SPIRAM);
if (!s_send_buf) {
ESP_LOGE(TAG, "Failed to allocate send buffer");
return ESP_ERR_NO_MEM;
}
jpeg_encode_engine_cfg_t enc_eng_cfg = {};
enc_eng_cfg.timeout_ms = 500;
err = jpeg_new_encoder_engine(&enc_eng_cfg, &s_jpeg_enc);
if (err != ESP_OK) {
ESP_LOGE(TAG, "JPEG encoder init failed: %s", esp_err_to_name(err));
return err;
}
err = esp_cam_ctlr_enable(s_cam_handle);
if (err != ESP_OK) {
ESP_LOGE(TAG, "CSI controller enable failed: %s", esp_err_to_name(err));
return err;
}
err = esp_cam_ctlr_start(s_cam_handle);
if (err != ESP_OK) {
ESP_LOGE(TAG, "CSI controller start failed: %s", esp_err_to_name(err));
return err;
}
s_cam_initialized = true;
s_capture_running = true;
xTaskCreatePinnedToCore(capture_task_fn, "csi_cap", 4096, NULL, 6, &s_capture_task, 1);
ESP_LOGI(TAG, "MIPI-CSI camera initialized (%dx%d, %d-lane, %d Mbps)", s_frame_hres, s_frame_vres,
MIPI_CSI_DATA_LANES, MIPI_CSI_LANE_BITRATE_MBPS);
return ESP_OK;
}
esp_err_t CameraService::cameraStill(httpd_req_t *request) {
if (!s_cam_initialized) {
return WebServer::sendError(request, 503, "Camera not initialized");
}
if (xSemaphoreTake(s_jpeg_ready, pdMS_TO_TICKS(3000)) != pdTRUE) {
return WebServer::sendError(request, 500, "Camera capture timed out");
}
xSemaphoreTake(s_jpeg_lock, portMAX_DELAY);
size_t len = s_ready_jpeg_len;
if (s_ready_idx >= 0 && len > 0) {
memcpy(s_send_buf, s_jpeg_bufs[s_ready_idx], len);
}
xSemaphoreGive(s_jpeg_lock);
if (len == 0) {
return WebServer::sendError(request, 500, "No frame available");
}
httpd_resp_set_type(request, "image/jpeg");
httpd_resp_set_hdr(request, "Content-Disposition", "inline; filename=capture.jpg");
return httpd_resp_send(request, (const char *)s_send_buf, len);
}
esp_err_t CameraService::cameraStream(httpd_req_t *request) {
if (!s_cam_initialized) {
return WebServer::sendError(request, 503, "Camera not initialized");
}
httpd_resp_set_type(request, _STREAM_CONTENT_TYPE);
char part_buf[64];
esp_err_t res = ESP_OK;
while (res == ESP_OK) {
if (xSemaphoreTake(s_jpeg_ready, pdMS_TO_TICKS(3000)) != pdTRUE) {
break;
}
xSemaphoreTake(s_jpeg_lock, portMAX_DELAY);
size_t jpeg_len = s_ready_jpeg_len;
if (s_ready_idx >= 0 && jpeg_len > 0) {
memcpy(s_send_buf, s_jpeg_bufs[s_ready_idx], jpeg_len);
}
xSemaphoreGive(s_jpeg_lock);
if (jpeg_len == 0) continue;
size_t hlen = snprintf(part_buf, 64, _STREAM_PART, (unsigned int)jpeg_len);
res = httpd_resp_send_chunk(request, part_buf, hlen);
if (res == ESP_OK) res = httpd_resp_send_chunk(request, (const char *)s_send_buf, jpeg_len);
if (res == ESP_OK) res = httpd_resp_send_chunk(request, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
ESP_LOGI(TAG, "Stream ended");
httpd_resp_send_chunk(request, NULL, 0);
return ESP_OK;
}
#else
CameraService::CameraService() {}
esp_err_t CameraService::begin() { return ESP_ERR_NOT_SUPPORTED; }
esp_err_t CameraService::cameraStill(httpd_req_t *request) {
return WebServer::sendError(request, 501, "Camera not supported on this platform");
}
esp_err_t CameraService::cameraStream(httpd_req_t *request) {
return WebServer::sendError(request, 501, "Camera not supported on this platform");
}
#endif
} // namespace Camera
+11 -33
View File
@@ -16,40 +16,18 @@ void Peripherals::begin() {
updatePins();
#if FT_ENABLED(USE_ICM20948)
#if FT_ENABLED(USE_ICM20948_SPIMODE) > 0
ICM_20948_SPI* icm20948 = new ICM_20948_SPI;
#else
ICM_20948_I2C* icm20948 = new ICM_20948_I2C;
#endif
#endif
// --- IMU ---
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
if (!_imu.initialize(nullptr)) ESP_LOGE("Peripherals", "IMU initialize failed");
#elif FT_ENABLED(USE_ICM20948)
if (!_imu.initialize(icm20948)) ESP_LOGE("Peripherals", "IMU initialize failed (ICM20948)");
if (!_imu.initialize()) ESP_LOGE("IMUService", "IMU initialize failed");
#endif
// --- MAGNETOMETER ---
#if FT_ENABLED(USE_HMC5883)
if (!_mag.initialize(nullptr)) ESP_LOGE("Peripherals", "MAG initialize failed");
#elif FT_ENABLED(USE_ICM20948)
if (!_mag.initialize(icm20948)) ESP_LOGE("Peripherals", "MAG initialize failed (ICM20948)");
if (!_mag.initialize()) ESP_LOGE("IMUService", "MAG initialize failed");
#endif
// --- BMP ---
#if FT_ENABLED(USE_BMP180)
if (!_bmp.initialize(nullptr)) ESP_LOGE("Peripherals", "BMP initialize failed");
if (!_bmp.initialize()) ESP_LOGE("IMUService", "BMP initialize failed");
#endif
// --- GESTURE ---
#if FT_ENABLED(USE_PAJ7620U2)
if (!_gesture.initialize(nullptr)) ESP_LOGE("Peripherals", "Gesture initialize failed");
if (!_gesture.initialize()) ESP_LOGE("IMUService", "Gesture initialize failed");
#endif
// --- SONAR ---
#if FT_ENABLED(USE_USS)
_left_sonar = std::make_unique<NewPing>(USS_LEFT_PIN, USS_LEFT_PIN, MAX_DISTANCE);
_right_sonar = std::make_unique<NewPing>(USS_RIGHT_PIN, USS_RIGHT_PIN, MAX_DISTANCE);
@@ -96,7 +74,7 @@ void Peripherals::scanI2C(uint8_t lower, uint8_t higher) {
}
void Peripherals::getIMUProto(socket_message_IMUData &data) {
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
data.x = _imu.getAngleX();
data.y = _imu.getAngleY();
data.z = _imu.getAngleZ();
@@ -123,7 +101,7 @@ void Peripherals::getSettingsProto(socket_message_PeripheralSettingsData &data)
/* IMU FUNCTIONS */
bool Peripherals::readImu() {
bool updated = false;
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
beginTransaction();
updated = _imu.update();
endTransaction();
@@ -133,7 +111,7 @@ bool Peripherals::readImu() {
bool Peripherals::readMag() {
bool updated = false;
#if FT_ENABLED(USE_HMC5883 || USE_ICM20948)
#if FT_ENABLED(USE_HMC5883)
beginTransaction();
updated = _mag.update();
endTransaction();
@@ -171,7 +149,7 @@ void Peripherals::readSonar() {
float Peripherals::angleX() {
return
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
_imu.getAngleX();
#else
0;
@@ -180,7 +158,7 @@ float Peripherals::angleX() {
float Peripherals::angleY() {
return
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
_imu.getAngleY();
#else
0;
@@ -189,7 +167,7 @@ float Peripherals::angleY() {
float Peripherals::angleZ() {
return
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
_imu.getAngleZ();
#else
0;
@@ -209,7 +187,7 @@ float Peripherals::leftDistance() { return _left_distance; }
float Peripherals::rightDistance() { return _right_distance; }
bool Peripherals::calibrateIMU() {
#if FT_ENABLED(USE_MPU6050 || USE_BNO055 || USE_ICM20948)
#if FT_ENABLED(USE_MPU6050 || USE_BNO055)
beginTransaction();
bool result = _imu.calibrate();
endTransaction();
+138 -20
View File
@@ -1,5 +1,44 @@
#include "system_service.h"
#include <communication/webserver.h>
#include <dirent.h>
#include <esp_chip_info.h>
#include <esp_flash.h>
#include <esp_ota_ops.h>
#include <esp_system.h>
#include <esp_sleep.h>
#include <soc/soc.h>
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 || CONFIG_IDF_TARGET_ESP32C3 || \
CONFIG_IDF_TARGET_ESP32C6 || CONFIG_IDF_TARGET_ESP32P4
#include <driver/temperature_sensor.h>
static float temperatureRead() {
static temperature_sensor_handle_t temp_sensor = nullptr;
static bool initialized = false;
if (!initialized) {
temperature_sensor_config_t temp_sensor_config = {
.range_min = -10,
.range_max = 80,
.clk_src = TEMPERATURE_SENSOR_CLK_SRC_DEFAULT,
};
if (temperature_sensor_install(&temp_sensor_config, &temp_sensor) == ESP_OK) {
temperature_sensor_enable(temp_sensor);
initialized = true;
}
}
if (initialized && temp_sensor) {
float temp = 0;
if (temperature_sensor_get_celsius(temp_sensor, &temp) == ESP_OK) {
return temp;
}
}
return 0.0f;
}
#else
static inline float temperatureRead() { return 0.0f; }
#endif
namespace system_service {
@@ -22,12 +61,15 @@ esp_err_t handleSleep(httpd_req_t *request) {
void reset() {
ESP_LOGI(TAG, "Resetting device");
File root = ESP_FS.open(FS_CONFIG_DIRECTORY);
File file;
while (file = root.openNextFile()) {
std::string path = file.path();
file.close();
ESP_FS.remove(path.c_str());
DIR *dir = opendir(FS_CONFIG_DIRECTORY);
if (dir) {
struct dirent *entry;
while ((entry = readdir(dir)) != nullptr) {
if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) continue;
std::string path = std::string(FS_CONFIG_DIRECTORY) + "/" + entry->d_name;
remove(path.c_str());
}
closedir(dir);
}
restart();
}
@@ -37,11 +79,11 @@ void restart() {
[](void *pvParameters) {
for (;;) {
vTaskDelay(250 / portTICK_PERIOD_MS);
MDNS.end();
mdns_free();
vTaskDelay(100 / portTICK_PERIOD_MS);
WiFi.disconnect(true);
vTaskDelay(500 / portTICK_PERIOD_MS);
ESP.restart();
esp_restart();
}
},
"Restart task", 4096, nullptr, 10, nullptr);
@@ -52,14 +94,14 @@ void sleep() {
[](void *pvParameters) {
for (;;) {
vTaskDelay(250 / portTICK_PERIOD_MS);
MDNS.end();
mdns_free();
vTaskDelay(100 / portTICK_PERIOD_MS);
WiFi.disconnect(true);
vTaskDelay(500 / portTICK_PERIOD_MS);
uint64_t bitmask = (uint64_t)1 << (WAKEUP_PIN_NUMBER);
#ifdef CONFIG_IDF_TARGET_ESP32C3
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32C6 || CONFIG_IDF_TARGET_ESP32P4
esp_deep_sleep_enable_gpio_wakeup(bitmask, (esp_deepsleep_gpio_wake_up_mode_t)WAKEUP_SIGNAL);
#else
esp_sleep_enable_ext1_wakeup(bitmask, (esp_sleep_ext1_wakeup_mode_t)WAKEUP_SIGNAL);
@@ -72,22 +114,98 @@ void sleep() {
ESP_LOGI(TAG, "Setting device to sleep");
}
static const char *getChipModel() {
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
switch (chip_info.model) {
case CHIP_ESP32: return "ESP32";
case CHIP_ESP32S2: return "ESP32-S2";
case CHIP_ESP32S3: return "ESP32-S3";
case CHIP_ESP32C3: return "ESP32-C3";
case CHIP_ESP32C2: return "ESP32-C2";
case CHIP_ESP32C6: return "ESP32-C6";
case CHIP_ESP32H2: return "ESP32-H2";
case CHIP_ESP32P4: return "ESP32-P4";
default: return "Unknown";
}
}
static uint32_t getCpuFreqMHz() { return CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ; }
static uint8_t getChipCores() {
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
return chip_info.cores;
}
static uint8_t getChipRevision() {
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
return chip_info.revision;
}
static uint32_t getFlashChipSize() {
uint32_t size = 0;
esp_flash_get_size(NULL, &size);
return size;
}
static uint32_t getFlashChipSpeed() {
#if defined(CONFIG_ESPTOOLPY_FLASHFREQ_120M)
return 120000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_80M)
return 80000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_64M)
return 64000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_60M)
return 60000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_48M)
return 48000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_40M)
return 40000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_30M)
return 30000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_26M)
return 26000000;
#elif defined(CONFIG_ESPTOOLPY_FLASHFREQ_20M)
return 20000000;
#else
return 80000000;
#endif
}
static uint32_t getSketchSize() {
const esp_partition_t *running = esp_ota_get_running_partition();
if (running) {
return running->size;
}
return 0;
}
static uint32_t getFreeSketchSpace() {
const esp_partition_t *next = esp_ota_get_next_update_partition(NULL);
if (next) {
return next->size;
}
return 0;
}
void getStaticSystemInformation(socket_message_StaticSystemInformation &info) {
size_t fs_total = 0, fs_used = 0;
esp_littlefs_info("spiffs", &fs_total, &fs_used);
info.esp_platform = (char *)ESP_PLATFORM_NAME;
info.firmware_version = APP_VERSION;
info.cpu_freq_mhz = ESP.getCpuFreqMHz();
info.cpu_type = (char *)ESP.getChipModel();
info.cpu_rev = ESP.getChipRevision();
info.cpu_cores = ESP.getChipCores();
info.sketch_size = ESP.getSketchSize();
info.free_sketch_space = ESP.getFreeSketchSpace();
info.sdk_version = (char *)ESP.getSdkVersion();
info.arduino_version = ARDUINO_VERSION;
info.flash_chip_size = ESP.getFlashChipSize();
info.flash_chip_speed = ESP.getFlashChipSpeed();
info.cpu_freq_mhz = getCpuFreqMHz();
info.cpu_type = (char *)getChipModel();
info.cpu_rev = getChipRevision();
info.cpu_cores = getChipCores();
info.sketch_size = getSketchSize();
info.free_sketch_space = getFreeSketchSpace();
info.sdk_version = (char *)esp_get_idf_version();
info.arduino_version = "";
info.flash_chip_size = getFlashChipSize();
info.flash_chip_speed = getFlashChipSpeed();
info.cpu_reset_reason = (char *)resetReason(esp_reset_reason());
}
+571
View File
@@ -0,0 +1,571 @@
#include <wifi/wifi_idf.h>
static const char* TAG = "WiFiIDF";
WiFiClass WiFi;
WiFiClass::WiFiClass()
: _sta_netif(nullptr),
_ap_netif(nullptr),
_initialized(false),
_autoReconnect(false),
_persistent(false),
_status(WL_DISCONNECTED),
_mode(WIFI_MODE_NULL),
_scanResult(nullptr),
_scanCount(0),
_scanStatus(-2),
_useStaticIp(false) {}
WiFiClass::~WiFiClass() {
if (_scanResult) {
free(_scanResult);
_scanResult = nullptr;
}
}
bool WiFiClass::init() {
if (_initialized) return true;
esp_err_t ret = nvs_flash_init();
if (ret == ESP_ERR_NVS_NO_FREE_PAGES || ret == ESP_ERR_NVS_NEW_VERSION_FOUND) {
nvs_flash_erase();
ret = nvs_flash_init();
}
ret = esp_netif_init();
if (ret != ESP_OK && ret != ESP_ERR_INVALID_STATE) {
ESP_LOGE(TAG, "esp_netif_init failed: %s", esp_err_to_name(ret));
}
ret = esp_event_loop_create_default();
if (ret != ESP_OK && ret != ESP_ERR_INVALID_STATE) {
ESP_LOGE(TAG, "Event loop create failed: %s", esp_err_to_name(ret));
}
_sta_netif = esp_netif_get_handle_from_ifkey("WIFI_STA_DEF");
if (!_sta_netif) {
_sta_netif = esp_netif_create_default_wifi_sta();
}
_ap_netif = esp_netif_get_handle_from_ifkey("WIFI_AP_DEF");
if (!_ap_netif) {
_ap_netif = esp_netif_create_default_wifi_ap();
}
wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT();
ret = esp_wifi_init(&cfg);
if (ret != ESP_OK && ret != ESP_ERR_INVALID_STATE) {
ESP_LOGE(TAG, "esp_wifi_init failed: %s", esp_err_to_name(ret));
return false;
}
esp_event_handler_instance_register(WIFI_EVENT, ESP_EVENT_ANY_ID, &WiFiClass::eventHandler, this, nullptr);
esp_event_handler_instance_register(IP_EVENT, ESP_EVENT_ANY_ID, &WiFiClass::eventHandler, this, nullptr);
esp_wifi_set_storage(_persistent ? WIFI_STORAGE_FLASH : WIFI_STORAGE_RAM);
_initialized = true;
return true;
}
void WiFiClass::eventHandler(void* arg, esp_event_base_t event_base, int32_t event_id, void* event_data) {
WiFiClass* self = static_cast<WiFiClass*>(arg);
if (event_base == WIFI_EVENT) {
switch (event_id) {
case WIFI_EVENT_STA_START: ESP_LOGI(TAG, "STA Started"); break;
case WIFI_EVENT_STA_STOP:
ESP_LOGI(TAG, "STA Stopped");
self->_status = WL_DISCONNECTED;
break;
case WIFI_EVENT_STA_CONNECTED: ESP_LOGI(TAG, "STA Connected"); break;
case WIFI_EVENT_STA_DISCONNECTED: {
wifi_event_sta_disconnected_t* event = (wifi_event_sta_disconnected_t*)event_data;
ESP_LOGI(TAG, "STA Disconnected, reason: %d", event->reason);
self->_status = WL_DISCONNECTED;
if (self->_autoReconnect) {
esp_wifi_connect();
}
break;
}
case WIFI_EVENT_AP_START: ESP_LOGI(TAG, "AP Started"); break;
case WIFI_EVENT_AP_STOP: ESP_LOGI(TAG, "AP Stopped"); break;
case WIFI_EVENT_AP_STACONNECTED: {
wifi_event_ap_staconnected_t* event = (wifi_event_ap_staconnected_t*)event_data;
ESP_LOGI(TAG, "Station connected, AID=%d", event->aid);
break;
}
case WIFI_EVENT_AP_STADISCONNECTED: {
wifi_event_ap_stadisconnected_t* event = (wifi_event_ap_stadisconnected_t*)event_data;
ESP_LOGI(TAG, "Station disconnected, AID=%d", event->aid);
break;
}
case WIFI_EVENT_SCAN_DONE: {
wifi_event_sta_scan_done_t* event = (wifi_event_sta_scan_done_t*)event_data;
if (event->status == 0) {
self->_scanCount = event->number;
if (self->_scanResult) {
free(self->_scanResult);
}
self->_scanResult = (wifi_ap_record_t*)malloc(sizeof(wifi_ap_record_t) * self->_scanCount);
if (self->_scanResult) {
esp_wifi_scan_get_ap_records(&self->_scanCount, self->_scanResult);
}
self->_scanStatus = self->_scanCount;
} else {
self->_scanStatus = -2;
}
break;
}
}
self->dispatchEvent(event_id, event_data);
} else if (event_base == IP_EVENT) {
if (event_id == IP_EVENT_STA_GOT_IP) {
ip_event_got_ip_t* event = (ip_event_got_ip_t*)event_data;
ESP_LOGI(TAG, "Got IP: " IPSTR, IP2STR(&event->ip_info.ip));
self->_status = WL_CONNECTED;
self->dispatchEvent(event_id + 1000, event_data);
} else if (event_id == IP_EVENT_STA_LOST_IP) {
ESP_LOGI(TAG, "Lost IP");
self->_status = WL_DISCONNECTED;
self->dispatchEvent(event_id + 1000, event_data);
}
}
}
void WiFiClass::dispatchEvent(int32_t event_id, void* event_data) {
for (auto& handler : _eventHandlers) {
if (handler.event_id == event_id || handler.event_id == -1) {
handler.callback(event_id, event_data);
}
}
}
void WiFiClass::onEvent(WiFiEventCb callback, int32_t event_id) { _eventHandlers.push_back({event_id, callback}); }
bool WiFiClass::mode(wifi_mode_t m) {
if (!_initialized) init();
if (_mode == m) return true;
esp_err_t err;
if (_mode == WIFI_MODE_NULL) {
err = esp_wifi_set_mode(m);
if (err == ESP_OK) {
err = esp_wifi_start();
}
} else if (m == WIFI_MODE_NULL) {
err = esp_wifi_stop();
} else {
err = esp_wifi_set_mode(m);
}
if (err == ESP_OK) {
_mode = m;
return true;
}
ESP_LOGE(TAG, "Failed to set mode: %s", esp_err_to_name(err));
return false;
}
wifi_mode_t WiFiClass::getMode() {
if (!_initialized) return WIFI_MODE_NULL;
wifi_mode_t m;
if (esp_wifi_get_mode(&m) == ESP_OK) {
return m;
}
return WIFI_MODE_NULL;
}
bool WiFiClass::begin(const char* ssid, const char* password, int32_t channel, const uint8_t* bssid) {
if (!_initialized) init();
wifi_mode_t currentMode = getMode();
if (currentMode == WIFI_MODE_NULL || currentMode == WIFI_MODE_AP) {
mode(currentMode == WIFI_MODE_AP ? WIFI_MODE_APSTA : WIFI_MODE_STA);
vTaskDelay(500 / portTICK_PERIOD_MS);
}
wifi_config_t wifi_config = {};
strncpy((char*)wifi_config.sta.ssid, ssid, sizeof(wifi_config.sta.ssid) - 1);
if (password) {
strncpy((char*)wifi_config.sta.password, password, sizeof(wifi_config.sta.password) - 1);
}
if (channel > 0) {
wifi_config.sta.channel = channel;
}
if (bssid) {
memcpy(wifi_config.sta.bssid, bssid, 6);
wifi_config.sta.bssid_set = true;
}
wifi_config.sta.scan_method = WIFI_ALL_CHANNEL_SCAN;
wifi_config.sta.sort_method = WIFI_CONNECT_AP_BY_SIGNAL;
wifi_config.sta.threshold.authmode = password && strlen(password) > 0 ? WIFI_AUTH_WPA2_PSK : WIFI_AUTH_OPEN;
esp_err_t err = esp_wifi_set_config(WIFI_IF_STA, &wifi_config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to set STA config: %s", esp_err_to_name(err));
return false;
}
if (_useStaticIp) {
esp_netif_dhcpc_stop(_sta_netif);
esp_netif_ip_info_t ip_info = {};
ip_info.ip = _sta_static_ip;
ip_info.gw = _sta_static_gw;
ip_info.netmask = _sta_static_sn;
esp_netif_set_ip_info(_sta_netif, &ip_info);
if (static_cast<uint32_t>(_sta_static_dns1) != 0) {
esp_netif_dns_info_t dns;
dns.ip.u_addr.ip4 = _sta_static_dns1;
dns.ip.type = ESP_IPADDR_TYPE_V4;
esp_netif_set_dns_info(_sta_netif, ESP_NETIF_DNS_MAIN, &dns);
}
if (static_cast<uint32_t>(_sta_static_dns2) != 0) {
esp_netif_dns_info_t dns;
dns.ip.u_addr.ip4 = _sta_static_dns2;
dns.ip.type = ESP_IPADDR_TYPE_V4;
esp_netif_set_dns_info(_sta_netif, ESP_NETIF_DNS_BACKUP, &dns);
}
} else {
esp_netif_dhcpc_start(_sta_netif);
}
err = esp_wifi_connect();
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to connect: %s", esp_err_to_name(err));
return false;
}
return true;
}
bool WiFiClass::disconnect(bool wifiOff) {
esp_err_t err = esp_wifi_disconnect();
if (wifiOff) {
wifi_mode_t m = getMode();
if (m == WIFI_MODE_APSTA) {
mode(WIFI_MODE_AP);
} else if (m == WIFI_MODE_STA) {
mode(WIFI_MODE_NULL);
}
}
_status = WL_DISCONNECTED;
return err == ESP_OK;
}
bool WiFiClass::reconnect() { return esp_wifi_connect() == ESP_OK; }
bool WiFiClass::config(IPAddress local_ip, IPAddress gateway, IPAddress subnet, IPAddress dns1, IPAddress dns2) {
_sta_static_ip = local_ip;
_sta_static_gw = gateway;
_sta_static_sn = subnet;
_sta_static_dns1 = dns1;
_sta_static_dns2 = dns2;
_useStaticIp = (static_cast<uint32_t>(local_ip) != 0);
return true;
}
bool WiFiClass::setHostname(const char* hostname) {
_hostname = hostname;
if (_sta_netif) {
return esp_netif_set_hostname(_sta_netif, hostname) == ESP_OK;
}
return true;
}
const char* WiFiClass::getHostname() {
const char* hostname = nullptr;
if (_sta_netif) {
esp_netif_get_hostname(_sta_netif, &hostname);
}
return hostname ? hostname : _hostname.c_str();
}
wl_status_t WiFiClass::status() { return _status; }
bool WiFiClass::isConnected() { return _status == WL_CONNECTED; }
IPAddress WiFiClass::localIP() {
esp_netif_ip_info_t ip_info;
if (_sta_netif && esp_netif_get_ip_info(_sta_netif, &ip_info) == ESP_OK) {
return IPAddress(ip_info.ip);
}
return IPAddress();
}
IPAddress WiFiClass::subnetMask() {
esp_netif_ip_info_t ip_info;
if (_sta_netif && esp_netif_get_ip_info(_sta_netif, &ip_info) == ESP_OK) {
return IPAddress(ip_info.netmask);
}
return IPAddress();
}
IPAddress WiFiClass::gatewayIP() {
esp_netif_ip_info_t ip_info;
if (_sta_netif && esp_netif_get_ip_info(_sta_netif, &ip_info) == ESP_OK) {
return IPAddress(ip_info.gw);
}
return IPAddress();
}
IPAddress WiFiClass::dnsIP(uint8_t dns_no) {
esp_netif_dns_info_t dns;
esp_netif_dns_type_t type = dns_no == 0 ? ESP_NETIF_DNS_MAIN : ESP_NETIF_DNS_BACKUP;
if (_sta_netif && esp_netif_get_dns_info(_sta_netif, type, &dns) == ESP_OK) {
return IPAddress(dns.ip.u_addr.ip4);
}
return IPAddress();
}
std::string WiFiClass::macAddress() {
uint8_t mac[6];
char buf[18];
esp_wifi_get_mac(WIFI_IF_STA, mac);
snprintf(buf, sizeof(buf), "%02X:%02X:%02X:%02X:%02X:%02X", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
return std::string(buf);
}
std::string WiFiClass::SSID() {
wifi_ap_record_t info;
if (esp_wifi_sta_get_ap_info(&info) == ESP_OK) {
return std::string((char*)info.ssid);
}
return "";
}
std::string WiFiClass::BSSIDstr() {
wifi_ap_record_t info;
if (esp_wifi_sta_get_ap_info(&info) == ESP_OK) {
char buf[18];
snprintf(buf, sizeof(buf), "%02X:%02X:%02X:%02X:%02X:%02X", info.bssid[0], info.bssid[1], info.bssid[2],
info.bssid[3], info.bssid[4], info.bssid[5]);
return std::string(buf);
}
return "";
}
int32_t WiFiClass::RSSI() {
wifi_ap_record_t info;
if (esp_wifi_sta_get_ap_info(&info) == ESP_OK) {
return info.rssi;
}
return 0;
}
uint8_t WiFiClass::channel() {
wifi_ap_record_t info;
if (esp_wifi_sta_get_ap_info(&info) == ESP_OK) {
return info.primary;
}
return 0;
}
int16_t WiFiClass::scanNetworks(bool async) {
if (!_initialized) init();
wifi_mode_t currentMode = getMode();
if (currentMode == WIFI_MODE_NULL || currentMode == WIFI_MODE_AP) {
mode(currentMode == WIFI_MODE_AP ? WIFI_MODE_APSTA : WIFI_MODE_STA);
vTaskDelay(500 / portTICK_PERIOD_MS);
}
_scanStatus = -1;
wifi_scan_config_t scan_config = {};
scan_config.show_hidden = true;
esp_err_t err = esp_wifi_scan_start(&scan_config, !async);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Scan start failed: %s", esp_err_to_name(err));
_scanStatus = -2;
return -2;
}
if (!async) {
if (_scanResult) {
free(_scanResult);
_scanResult = nullptr;
}
esp_wifi_scan_get_ap_num(&_scanCount);
_scanResult = (wifi_ap_record_t*)malloc(sizeof(wifi_ap_record_t) * _scanCount);
if (_scanResult) {
esp_wifi_scan_get_ap_records(&_scanCount, _scanResult);
}
_scanStatus = _scanCount;
return _scanCount;
}
return -1;
}
int16_t WiFiClass::scanComplete() { return _scanStatus; }
void WiFiClass::scanDelete() {
if (_scanResult) {
free(_scanResult);
_scanResult = nullptr;
}
_scanCount = 0;
_scanStatus = -2;
}
std::string WiFiClass::SSID(uint8_t i) {
if (i < _scanCount && _scanResult) {
return std::string((char*)_scanResult[i].ssid);
}
return "";
}
int32_t WiFiClass::RSSI(uint8_t i) {
if (i < _scanCount && _scanResult) {
return _scanResult[i].rssi;
}
return 0;
}
wifi_enc_type_t WiFiClass::encryptionType(uint8_t i) {
if (i < _scanCount && _scanResult) {
switch (_scanResult[i].authmode) {
case WIFI_AUTH_OPEN: return WIFI_AUTH_OPEN_IDF;
case WIFI_AUTH_WEP: return WIFI_AUTH_WEP_IDF;
case WIFI_AUTH_WPA_PSK: return WIFI_AUTH_WPA_PSK_IDF;
default: return WIFI_AUTH_WPA2_PSK_IDF;
}
}
return WIFI_AUTH_OPEN_IDF;
}
std::string WiFiClass::BSSIDstr(uint8_t i) {
if (i < _scanCount && _scanResult) {
char buf[18];
snprintf(buf, sizeof(buf), "%02X:%02X:%02X:%02X:%02X:%02X", _scanResult[i].bssid[0], _scanResult[i].bssid[1],
_scanResult[i].bssid[2], _scanResult[i].bssid[3], _scanResult[i].bssid[4], _scanResult[i].bssid[5]);
return std::string(buf);
}
return "";
}
int32_t WiFiClass::channel(uint8_t i) {
if (i < _scanCount && _scanResult) {
return _scanResult[i].primary;
}
return 0;
}
void WiFiClass::getNetworkInfo(uint8_t i, std::string& ssid, uint8_t& encType, int32_t& rssi, uint8_t*& bssid,
int32_t& ch) {
if (i < _scanCount && _scanResult) {
ssid = std::string((char*)_scanResult[i].ssid);
encType = static_cast<uint8_t>(encryptionType(i));
rssi = _scanResult[i].rssi;
bssid = _scanResult[i].bssid;
ch = _scanResult[i].primary;
}
}
bool WiFiClass::softAP(const char* ssid, const char* password, int channel, bool ssid_hidden, int max_connection) {
if (!_initialized) init();
wifi_mode_t currentMode = getMode();
if (currentMode == WIFI_MODE_NULL || currentMode == WIFI_MODE_STA) {
mode(currentMode == WIFI_MODE_STA ? WIFI_MODE_APSTA : WIFI_MODE_AP);
}
wifi_config_t wifi_config = {};
strncpy((char*)wifi_config.ap.ssid, ssid, sizeof(wifi_config.ap.ssid) - 1);
wifi_config.ap.ssid_len = strlen(ssid);
wifi_config.ap.channel = channel;
wifi_config.ap.ssid_hidden = ssid_hidden ? 1 : 0;
wifi_config.ap.max_connection = max_connection;
if (password && strlen(password) > 0) {
strncpy((char*)wifi_config.ap.password, password, sizeof(wifi_config.ap.password) - 1);
wifi_config.ap.authmode = WIFI_AUTH_WPA2_PSK;
} else {
wifi_config.ap.authmode = WIFI_AUTH_OPEN;
}
esp_err_t err = esp_wifi_set_config(WIFI_IF_AP, &wifi_config);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to set AP config: %s", esp_err_to_name(err));
return false;
}
return true;
}
bool WiFiClass::softAPConfig(IPAddress local_ip, IPAddress gateway, IPAddress subnet) {
if (!_ap_netif) return false;
esp_netif_dhcps_stop(_ap_netif);
esp_netif_ip_info_t ip_info = {};
ip_info.ip = local_ip;
ip_info.gw = gateway;
ip_info.netmask = subnet;
esp_err_t err = esp_netif_set_ip_info(_ap_netif, &ip_info);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to set AP IP info: %s", esp_err_to_name(err));
return false;
}
esp_netif_dhcps_start(_ap_netif);
return true;
}
bool WiFiClass::softAPdisconnect(bool wifiOff) {
wifi_mode_t m = getMode();
if (wifiOff) {
if (m == WIFI_MODE_APSTA) {
return mode(WIFI_MODE_STA);
} else if (m == WIFI_MODE_AP) {
return mode(WIFI_MODE_NULL);
}
}
return true;
}
IPAddress WiFiClass::softAPIP() {
esp_netif_ip_info_t ip_info;
if (_ap_netif && esp_netif_get_ip_info(_ap_netif, &ip_info) == ESP_OK) {
return IPAddress(ip_info.ip);
}
return IPAddress();
}
std::string WiFiClass::softAPmacAddress() {
uint8_t mac[6];
char buf[18];
esp_wifi_get_mac(WIFI_IF_AP, mac);
snprintf(buf, sizeof(buf), "%02X:%02X:%02X:%02X:%02X:%02X", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
return std::string(buf);
}
uint8_t WiFiClass::softAPgetStationNum() {
wifi_sta_list_t sta_list;
if (esp_wifi_ap_get_sta_list(&sta_list) == ESP_OK) {
return sta_list.num;
}
return 0;
}
bool WiFiClass::setAutoReconnect(bool autoReconnect) {
_autoReconnect = autoReconnect;
return true;
}
bool WiFiClass::persistent(bool persistent) {
_persistent = persistent;
if (_initialized) {
return esp_wifi_set_storage(persistent ? WIFI_STORAGE_FLASH : WIFI_STORAGE_RAM) == ESP_OK;
}
return true;
}
bool WiFiClass::setTxPower(int8_t power) { return esp_wifi_set_max_tx_power(power * 4) == ESP_OK; }
+62 -93
View File
@@ -1,45 +1,57 @@
#include <wifi_service.h>
#include <communication/webserver.h>
static const char *TAG = "WiFiService";
WiFiService::WiFiService()
: _persistence(WiFiSettings_read, WiFiSettings_update, this, WIFI_SETTINGS_FILE,
api_WifiSettings_fields, api_WifiSettings_size, WiFiSettings_defaults()),
protoEndpoint(WiFiSettings_read, WiFiSettings_update, this,
: protoEndpoint(WiFiSettings_read, WiFiSettings_update, this,
API_REQUEST_EXTRACTOR(wifi_settings, api_WifiSettings),
API_RESPONSE_ASSIGNER(wifi_settings, api_WifiSettings)) {
API_RESPONSE_ASSIGNER(wifi_settings, api_WifiSettings)),
_persistence(WiFiSettings_read, WiFiSettings_update, this, WIFI_SETTINGS_FILE, api_WifiSettings_fields,
api_WifiSettings_size, WiFiSettings_defaults()),
_lastConnectionAttempt(0),
_stopping(false) {
addUpdateHandler([&](const std::string &originId) { reconfigureWiFiConnection(); }, false);
}
WiFiService::~WiFiService() {}
void WiFiService::begin() {
WiFi.mode(WIFI_MODE_STA);
WiFi.persistent(false);
WiFi.setAutoReconnect(false);
WiFi.onEvent(std::bind(&WiFiService::onStationModeDisconnected, this, std::placeholders::_1, std::placeholders::_2),
WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED);
WiFi.onEvent(std::bind(&WiFiService::onStationModeStop, this, std::placeholders::_1, std::placeholders::_2),
WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_STOP);
WiFi.onEvent(onStationModeGotIP, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_GOT_IP);
WiFi.onEvent([this](int32_t event, void *data) { this->onStationModeDisconnected(event, data); },
WIFI_EVENT_STA_DISCONNECTED);
WiFi.onEvent([this](int32_t event, void *data) { this->onStationModeStop(event, data); }, WIFI_EVENT_STA_STOP);
WiFi.onEvent(onStationModeGotIP, IP_EVENT_STA_GOT_IP_IDF);
_persistence.readFromFS();
reconfigureWiFiConnection();
_lastConnectionAttempt = 0;
if (state().wifi_networks_count == 1) {
configureNetwork(state().wifi_networks[0]);
vTaskDelay(500 / portTICK_PERIOD_MS);
if (state().wifi_networks_count >= 1) {
WiFi.mode(WIFI_MODE_STA);
vTaskDelay(100 / portTICK_PERIOD_MS);
uint32_t idx = state().selected_network;
if (idx >= state().wifi_networks_count) idx = 0;
configureNetwork(state().wifi_networks[idx]);
}
}
void WiFiService::reconfigureWiFiConnection() {
_lastConnectionAttempt = 0;
if (WiFi.disconnect(true)) _stopping = true;
}
void WiFiService::selectNetwork(uint32_t index) {
if (index >= state().wifi_networks_count) return;
updateWithoutPropagation([&](WiFiSettings &settings) {
settings.selected_network = index;
return StateUpdateResult::CHANGED;
});
_persistence.writeToFS();
reconfigureWiFiConnection();
}
void WiFiService::loop() { EXECUTE_EVERY_N_MS(reconnectDelay, manageSTA()); }
esp_err_t WiFiService::handleScan(httpd_req_t *request) {
@@ -47,7 +59,6 @@ esp_err_t WiFiService::handleScan(httpd_req_t *request) {
WiFi.scanDelete();
WiFi.scanNetworks(true);
}
// Return 202 with empty_message payload (no pointer fields to encode)
api_Response response = api_Response_init_zero;
response.status_code = 202;
response.which_payload = api_Response_empty_message_tag;
@@ -57,7 +68,6 @@ esp_err_t WiFiService::handleScan(httpd_req_t *request) {
esp_err_t WiFiService::getNetworks(httpd_req_t *request) {
int numNetworks = WiFi.scanComplete();
if (numNetworks == -1) {
// Scan in progress - return 202 with empty_message payload
api_Response response = api_Response_init_zero;
response.status_code = 202;
response.which_payload = api_Response_empty_message_tag;
@@ -66,10 +76,8 @@ esp_err_t WiFiService::getNetworks(httpd_req_t *request) {
return handleScan(request);
}
// Limit to 20 networks max
size_t count = (numNetworks > 20) ? 20 : static_cast<size_t>(numNetworks);
// Allocate networks array on stack (pointer type in proto)
api_WifiNetworkScan networks[20] = {};
for (size_t i = 0; i < count; i++) {
@@ -90,11 +98,13 @@ esp_err_t WiFiService::getNetworks(httpd_req_t *request) {
}
void WiFiService::setupMDNS(const char *hostname) {
MDNS.begin(state().hostname);
MDNS.setInstanceName(hostname);
MDNS.addService("http", "tcp", 80);
MDNS.addService("ws", "tcp", 80);
MDNS.addServiceTxt("http", "tcp", "Firmware Version", APP_VERSION);
mdns_init();
mdns_hostname_set(state().hostname);
mdns_instance_name_set(hostname);
mdns_service_add(nullptr, "_http", "_tcp", 80, nullptr, 0);
mdns_service_add(nullptr, "_ws", "_tcp", 80, nullptr, 0);
mdns_txt_item_t txtData = {"Firmware Version", APP_VERSION};
mdns_service_txt_set("_http", "_tcp", &txtData, 1);
}
esp_err_t WiFiService::getNetworkStatus(httpd_req_t *request) {
@@ -114,7 +124,6 @@ esp_err_t WiFiService::getNetworkStatus(httpd_req_t *request) {
wifiStatus.channel = WiFi.channel();
wifiStatus.subnet_mask = static_cast<uint32_t>(WiFi.subnetMask());
wifiStatus.gateway_ip = static_cast<uint32_t>(WiFi.gatewayIP());
IPAddress dnsIP1 = WiFi.dnsIP(0);
IPAddress dnsIP2 = WiFi.dnsIP(1);
if (dnsIP1 != IPAddress(0, 0, 0, 0)) {
@@ -130,98 +139,58 @@ esp_err_t WiFiService::getNetworkStatus(httpd_req_t *request) {
void WiFiService::manageSTA() {
if (WiFi.isConnected() || state().wifi_networks_count == 0) return;
if ((WiFi.getMode() & WIFI_STA) == 0) connectToWiFi();
}
wifi_mode_t mode = WiFi.getMode();
if (mode == WIFI_MODE_NULL || mode == WIFI_MODE_AP) return;
void WiFiService::connectToWiFi() {
int scanResult = WiFi.scanNetworks();
if (scanResult == WIFI_SCAN_FAILED) {
ESP_LOGE("WiFiSettingsService", "WiFi scan failed.");
} else if (scanResult == 0) {
ESP_LOGI("WiFiSettingsService", "No networks found.");
} else {
ESP_LOGI("WiFiSettingsService", "%d networks found.", scanResult);
static uint32_t startTime = 0;
static bool attempted = false;
WiFiNetwork *bestNetwork = nullptr;
int32_t bestNetworkDb = FACTORY_WIFI_RSSI_THRESHOLD;
if (startTime == 0) {
startTime = esp_timer_get_time() / 1000;
return;
}
for (int i = 0; i < scanResult; ++i) {
String ssid_scan;
int32_t rssi_scan;
uint8_t sec_scan;
uint8_t *BSSID_scan;
int32_t chan_scan;
uint32_t now = esp_timer_get_time() / 1000;
if (now - startTime < 3000) return;
WiFi.getNetworkInfo(i, ssid_scan, sec_scan, rssi_scan, BSSID_scan, chan_scan);
for (pb_size_t j = 0; j < state().wifi_networks_count; j++) {
WiFiNetwork &network = state().wifi_networks[j];
if (ssid_scan == network.ssid) {
if (rssi_scan >= FACTORY_WIFI_RSSI_THRESHOLD) {
// Network is available
}
if (rssi_scan > bestNetworkDb) {
bestNetworkDb = rssi_scan;
bestNetwork = &network;
}
}
}
}
if (!state().priority_rssi) {
for (pb_size_t j = 0; j < state().wifi_networks_count; j++) {
WiFiNetwork &network = state().wifi_networks[j];
// Check if this network was found in scan
for (int i = 0; i < scanResult; ++i) {
if (WiFi.SSID(i) == network.ssid) {
ESP_LOGI("WiFiSettingsService", "Connecting to first available network: %s", network.ssid);
configureNetwork(network);
WiFi.scanDelete();
return;
}
}
}
} else if (bestNetwork) {
ESP_LOGI("WiFiSettingsService", "Connecting to strongest network: %s", bestNetwork->ssid);
configureNetwork(*bestNetwork);
} else {
ESP_LOGI("WiFiSettingsService", "No known networks found.");
}
WiFi.scanDelete();
if (!attempted && state().wifi_networks_count > 0) {
attempted = true;
uint32_t idx = state().selected_network;
if (idx >= state().wifi_networks_count) idx = 0;
ESP_LOGI(TAG, "Connecting to: %s", state().wifi_networks[idx].ssid);
configureNetwork(state().wifi_networks[idx]);
}
}
void WiFiService::configureNetwork(WiFiNetwork &network) {
if (network.static_ip_config) {
WiFi.config(IPAddress(network.local_ip), IPAddress(network.gateway_ip),
IPAddress(network.subnet_mask), IPAddress(network.dns_ip_1), IPAddress(network.dns_ip_2));
WiFi.config(IPAddress(network.local_ip), IPAddress(network.gateway_ip), IPAddress(network.subnet_mask),
IPAddress(network.dns_ip_1), IPAddress(network.dns_ip_2));
} else {
WiFi.config(IPAddress(0, 0, 0, 0), IPAddress(0, 0, 0, 0), IPAddress(0, 0, 0, 0));
}
WiFi.setHostname(state().hostname);
WiFi.begin(network.ssid, network.password);
#if CONFIG_IDF_TARGET_ESP32C3
WiFi.setTxPower(WIFI_POWER_8_5dBm);
WiFi.setTxPower(8);
#endif
}
void WiFiService::onStationModeDisconnected(WiFiEvent_t event, WiFiEventInfo_t info) {
void WiFiService::onStationModeDisconnected(int32_t event, void *event_data) {
WiFi.disconnect(true);
ESP_LOGI("WiFiStatus", "WiFi Disconnected. Reason code=%d", info.wifi_sta_disconnected.reason);
wifi_event_sta_disconnected_t *info = static_cast<wifi_event_sta_disconnected_t *>(event_data);
ESP_LOGI(TAG, "WiFi Disconnected. Reason code=%d", info ? info->reason : 0);
}
void WiFiService::onStationModeStop(WiFiEvent_t event, WiFiEventInfo_t info) {
void WiFiService::onStationModeStop(int32_t event, void *event_data) {
if (_stopping) {
_lastConnectionAttempt = 0;
_stopping = false;
}
ESP_LOGI("WiFiStatus", "WiFi Connected.");
ESP_LOGI(TAG, "WiFi STA stopped.");
}
void WiFiService::onStationModeGotIP(WiFiEvent_t event, WiFiEventInfo_t info) {
ESP_LOGI("WiFiStatus", "WiFi Got IP. localIP=%s, hostName=%s", WiFi.localIP().toString().c_str(),
WiFi.getHostname());
void WiFiService::onStationModeGotIP(int32_t event, void *event_data) {
ESP_LOGI(TAG, "WiFi Got IP. localIP=%s, hostName=%s", WiFi.localIP().toString().c_str(), WiFi.getHostname());
}
+25 -2
View File
@@ -1,4 +1,14 @@
#include "www_mount.hpp"
#include <cstring>
static const WebAsset* findAsset(const char* uri) {
for (size_t i = 0; i < WWW_ASSETS_COUNT; i++) {
if (strcmp(WWW_ASSETS[i].uri, uri) == 0) {
return &WWW_ASSETS[i];
}
}
return nullptr;
}
static esp_err_t web_send(httpd_req_t* req, const WebAsset& asset) {
httpd_resp_set_status(req, "200 OK");
@@ -7,11 +17,11 @@ static esp_err_t web_send(httpd_req_t* req, const WebAsset& asset) {
if (WWW_OPT.add_vary) httpd_resp_set_hdr(req, "Vary", "Accept-Encoding");
char cc[64];
snprintf(cc, sizeof(cc), "public, immutable, max-age=%u", WWW_OPT.max_age);
snprintf(cc, sizeof(cc), "public, immutable, max-age=%lu", (unsigned long)WWW_OPT.max_age);
httpd_resp_set_hdr(req, "Cache-Control", cc);
char et[34];
snprintf(et, sizeof(et), "\"%08x\"", asset.etag);
snprintf(et, sizeof(et), "\"%08lx\"", (unsigned long)asset.etag);
httpd_resp_set_hdr(req, "ETag", et);
return httpd_resp_send(req, (const char*)asset.data, asset.len);
@@ -23,3 +33,16 @@ void mountStaticAssets(WebServer& server) {
server.on(a->uri, HTTP_GET, [a](httpd_req_t* req) { return web_send(req, *a); });
}
}
void mountSpaFallback(WebServer& server) {
const WebAsset* indexAsset = findAsset(WWW_OPT.default_uri);
if (indexAsset) {
server.on("/*", HTTP_GET, [indexAsset](httpd_req_t* req) {
if (strncmp(req->uri, "/api/", 5) == 0) {
httpd_resp_send_err(req, HTTPD_404_NOT_FOUND, "Not found");
return ESP_FAIL;
}
return web_send(req, *indexAsset);
});
}
}
+1
View File
@@ -82,6 +82,7 @@ message WifiSettings {
string hostname = 1;
bool priority_rssi = 2;
repeated WifiNetwork wifi_networks = 3; // max 5 networks
uint32 selected_network = 4;
}
message WifiSettingsRequest {}
+54 -22
View File
@@ -15,6 +15,7 @@ src_dir = esp32/src
include_dir = esp32/include
lib_dir = esp32/lib
test_dir = esp32/test
boards_dir = boards
extra_configs =
esp32/factory_settings.ini
esp32/features.ini
@@ -40,14 +41,13 @@ build_flags=
[env:esp32-wroom-camera]
board = esp32-s3-devkitc-1
board_build.arduino.memory_type = qio_opi
board_build.flash_mode = qio
board_upload.flash_size = 8MB
upload_speed = 921600
board_build.partitions = esp32/partition_table/default_8MB.csv
build_flags =
${env.build_flags}
-DBOARD_HAS_PSRAM
-mfix-esp32-psram-cache-issue
-D USE_CAMERA=1
-D CAMERA_MODEL_ESP32S3_EYE=1
-D WS2812_PIN=48
@@ -55,10 +55,6 @@ build_flags =
-D USS_RIGHT_PIN=14
-D SDA_PIN=47
-D SCL_PIN=21
-D SPI_SCK=41
-D SPI_MISO=19
-D SPI_MOSI=20
-D ICM20948_SPI_CS=2 # Only needed if ICM20948 is in SPI mode
[env:seeed-xiao-esp32s3]
platform = espressif32
@@ -78,23 +74,60 @@ board_build.partitions = esp32/partition_table/min_spiffs.csv
build_flags =
${env.build_flags}
[env:esp32-p4]
platform = https://github.com/pioarduino/platform-espressif32.git
framework = espidf
board = esp32p4_dev
board_build.mcu = esp32p4
board_build.f_cpu = 360000000L
board_build.f_flash = 80000000L
board_build.f_psram = 200000000L
board_build.flash_mode = qio
board_upload.flash_size = 32MB
board_build.partitions = esp32/partition_table/default_32MB.csv
board_build.filesystem = littlefs
board_build.sdkconfig_defaults =
esp32/sdkconfig.defaults
esp32/sdkconfig.defaults.esp32p4
upload_speed = 921600
monitor_speed = 115200
monitor_filters =
direct
esp32_exception_decoder
extra_scripts =
pre:esp32/scripts/pre_build.py
pre:esp32/scripts/build_app.py
build_flags =
${env.build_flags}
-D USE_CAMERA=1
-D CAM_XCLK_PIN=-1
-D CAM_RESET_PIN=-1
-D CAM_PWDN_PIN=-1
-D MIPI_CSI_HRES=800
-D MIPI_CSI_VRES=640
-D MIPI_CSI_LANE_BITRATE_MBPS=400
-D MIPI_CSI_DATA_LANES=2
-D CSI_JPEG_QUALITY=65
-D BOARD_HAS_PSRAM
-D SDA_PIN=7
-D SCL_PIN=8
-D WS2812_PIN=27
; ================================================================
; General environment section
[env]
platform = espressif32 @ 6.8.1
framework = arduino
framework = espidf
monitor_speed = 115200
monitor_filters =
esp32_exception_decoder
default
colorize
monitor_filters =
direct
esp32_exception_decoder
build_flags =
${factory_settings.build_flags}
${features.build_flags}
${build_settings.build_flags}
-D SPI_PORT=SPI # Define which spi port to use for external components
-D CORE_DEBUG_LEVEL=4
-D register=
-std=gnu++2a
@@ -103,26 +136,25 @@ build_flags =
-fdata-sections
-Wl,--gc-sections
-I submodules/nanopb
-Wno-missing-braces ; Added to suppress protobufs extra nested braces causing warning
-Wno-missing-braces
-Wno-format
-D CONFIG_HTTPD_WS_SUPPORT=1
build_unflags = -std=gnu++11
build_src_filter =
+<*>
+<../../submodules/nanopb/pb_*.c>
build_src_flags =
-Wformat=2
-Wformat-truncation
-Wstack-usage=4096
-Wno-format
test_ignore = test_embedded
board_build.filesystem = littlefs
board_build.embed_txtfiles =
board_build.sdkconfig_defaults = esp32/sdkconfig.defaults
lib_deps =
ArduinoJson@>=7.0.0
teckel12/NewPing@^1.9.7
FastLED@3.5.0
sparkfun/SparkFun 9DoF IMU Breakout - ICM 20948 - Arduino Library@^1.3.2
lib_ldf_mode = deep
lib_compat_mode = strict
extra_scripts =
pre:esp32/scripts/pre_build.py
pre:esp32/scripts/build_app.py
lib_compat_mode = strict
; debug_tool = esp-builtin
; debug_init_break =
; upload_port = COM[13] # Only use this when upload port is not correctly detected due to multiple COM ports attached.
; upload_port = COM[13] # Only use this when upload port is not correctly detected due to multiple COM ports attached.
+5 -5
View File
@@ -143,8 +143,8 @@ A PyBullet-based physics simulation is available for algorithm development and r
```bash
cd simulation
pip install -r requirements.txt
python play.py
uv sync
uv run play.py
```
Features:
@@ -245,7 +245,7 @@ Complete build instructions are available in the documentation:
**Build and flash:**
```bash
git clone https://github.com/runeharlyk/SpotMicroESP32-Leika
git clone --recurse-submodules https://github.com/runeharlyk/SpotMicroESP32-Leika
cd SpotMicroESP32-Leika
cd app
@@ -264,8 +264,8 @@ To experiment with the simulation environments without hardware:
```bash
cd simulation
pip install -r requirements.txt
python play.py
uv sync
uv run play.py
```
For development workflows and contribution guidelines, see [docs/6_developing.md](docs/6_developing.md) and [docs/7_contributing.md](docs/7_contributing.md).
+40
View File
@@ -0,0 +1,40 @@
# HTTP Server WebSocket support
CONFIG_HTTPD_WS_SUPPORT=y
CONFIG_HTTPD_MAX_REQ_HDR_LEN=2048
CONFIG_HTTPD_MAX_URI_LEN=1024
# mDNS
CONFIG_MDNS_MAX_SERVICES=10
# LittleFS
CONFIG_LITTLEFS_MAX_PARTITIONS=3
#
# ESP System Settings
#
# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set
# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set
CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y
CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240
# Main task stack
CONFIG_ESP_MAIN_TASK_STACK_SIZE=8192
CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=4096
# PSRAM for S3
CONFIG_SPIRAM=y
CONFIG_SPIRAM_MODE_OCT=y
CONFIG_SPIRAM_SPEED_80M=y
# DSP library
CONFIG_DSP_MAX_FFT_SIZE_4096=y
# Compiler
CONFIG_COMPILER_OPTIMIZATION_PERF=y
# Partition table
CONFIG_PARTITION_TABLE_CUSTOM=y
# CONFIG_FATFS_LFN_NONE is not set
# CONFIG_FATFS_LFN_HEAP is not set
CONFIG_FATFS_LFN_STACK=y
+1
View File
@@ -0,0 +1 @@
3.13
+21
View File
@@ -0,0 +1,21 @@
[project]
name = "simulation-leika"
version = "0.1.0"
description = "Add your description here"
readme = "README.md"
requires-python = ">=3.13"
dependencies = [
"gymnasium>=1.2.3",
"matplotlib>=3.10.9",
"msgpack>=1.1.2",
"numpy>=2.4.4",
"onnx>=1.21.0",
"onnxruntime>=1.26.0",
"pybullet>=3.2.7",
"stable-baselines3[extra]>=2.0.0",
"tensorboard>=2.20.0",
"tensorflow>=2.21.0",
"torch>=2.11.0",
"tqdm>=4.67.3",
"websockets>=16.0",
]
-14
View File
@@ -1,14 +0,0 @@
torch
onnx
onnxruntime
tensorflow
numpy
matplotlib
pybullet
websockets
msgpack
asyncio
gymnasium
stable-baselines3[extra]>=2.0.0
tensorboard
tqdm
-24
View File
@@ -1,24 +0,0 @@
from src.envs.quadruped_env import QuadrupedEnv
from training.model import SimpleNN
import resources as resources
def main():
env = QuadrupedEnv(resources.getDataPath() + "/spot.urdf")
env.reset()
input_size = env.robot.get_observation().shape[0]
output_size = env.robot.get_observation().shape[0]
agent = SimpleNN(input_size, output_size)
done = False
observation = []
while not done:
action = agent.select_action(observation)
observation, reward, done = env.step(action)
if __name__ == "__main__":
main()
+1724
View File
File diff suppressed because it is too large Load Diff