Full migration to esp-idf

This commit is contained in:
Rune Harlyk
2026-01-31 15:30:36 +01:00
committed by Rune Harlyk
parent 21ed3d51d2
commit aca8ee6de5
42 changed files with 1815 additions and 343 deletions
+5
View File
@@ -6,6 +6,11 @@ __pycache__/
*.py[cod]
*$py.class
.pio
managed_components/
dependencies.lock
sdkconfig
sdkconfig.*
!esp32/sdkconfig.defaults
esp32/src/platform_shared/*
!esp32/src/platform_shared/.gitkeep
app/src/lib/platform_shared/*
+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)
+6 -4
View File
@@ -5,8 +5,10 @@
#include <template/stateful_persistence_pb.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
+1 -1
View File
@@ -1,6 +1,6 @@
#pragma once
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <ArduinoJson.h>
#include <esp_http_server.h>
#include "platform_shared/message.pb.h"
+25 -2
View File
@@ -2,11 +2,15 @@
#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 MOUNT_POINT "/littlefs"
#define FS_CONFIG_DIRECTORY "/config"
#define DEVICE_CONFIG_FILE "/config/peripheral.json"
@@ -24,6 +28,25 @@ 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);
#define AP_SETTINGS_FILE MOUNT_POINT "/config/apSettings.json"
#define CAMERA_SETTINGS_FILE MOUNT_POINT "/config/cameraSettings.json"
#define FS_CONFIG_DIRECTORY MOUNT_POINT "/config"
#define DEVICE_CONFIG_FILE MOUNT_POINT "/config/peripheral.json"
#define WIFI_SETTINGS_FILE MOUNT_POINT "/config/wifiSettings.json"
#define SERVO_SETTINGS_FILE MOUNT_POINT "/config/servoSettings.json"
#define MDNS_SETTINGS_FILE MOUNT_POINT "/config/mdnsSettings.json"
namespace FileSystem {
bool init();
std::string listFiles(const std::string &directory, bool isRoot = true);
bool deleteFile(const char *filename);
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 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 = "");
};
+6 -17
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
@@ -26,23 +27,11 @@
#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
*/
#ifndef SDA_PIN
#define SDA_PIN SDA
#define SDA_PIN 21
#endif
#ifndef SCL_PIN
#define SCL_PIN SCL
#define SCL_PIN 22
#endif
#ifndef I2C_FREQUENCY
#define I2C_FREQUENCY 100000UL
+2 -1
View File
@@ -1,7 +1,8 @@
#pragma once
#include <esp_http_server.h>
#include <ESPmDNS.h>
#include <ArduinoJson.h>
#include <mdns.h>
#include <template/stateful_service.h>
#include <template/stateful_proto_endpoint.h>
#include <template/stateful_persistence_pb.h>
+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,7 +1,6 @@
#pragma once
#include <esp_http_server.h>
#include <WiFi.h>
#include <features.h>
#include <template/stateful_service.h>
+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);
}
+71 -22
View File
@@ -1,55 +1,104 @@
#ifndef LEDService_h
#define LEDService_h
#include <FastLED.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
#define WS2812_PIN 12
#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);
}
};
+2
View File
@@ -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>
+3 -3
View File
@@ -1,12 +1,12 @@
#pragma once
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <wifi/dns_server.h>
#include <ArduinoJson.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
-1
View File
@@ -1,4 +1,3 @@
#include <Arduino.h>
#include <template/state_result.h>
#include <ArduinoJson.h>
#include <string>
+2 -1
View File
@@ -1,6 +1,7 @@
#pragma once
#include <WiFi.h>
#include <wifi/wifi_idf.h>
#include <ArduinoJson.h>
#include <template/state_result.h>
#include <platform_shared/api.pb.h>
#include <cstring>
+2 -2
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>
+14 -40
View File
@@ -1,24 +1,11 @@
#ifndef FSPersistence_h
#define FSPersistence_h
/**
* 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 <filesystem.h>
#include <ArduinoJson.h>
#include <cstdio>
#include <sys/stat.h>
template <class T>
class FSPersistence {
@@ -34,25 +21,18 @@ class FSPersistence {
}
void readFromFS() {
File settingsFile = _fs->open(_filePath, "r");
std::string content = FileSystem::readFile(_filePath);
if (settingsFile) {
if (!content.empty()) {
JsonDocument jsonDocument;
DeserializationError error = deserializeJson(jsonDocument, settingsFile);
DeserializationError error = deserializeJson(jsonDocument, content);
if (error == DeserializationError::Ok) {
JsonVariant jsonObject = jsonDocument.as<JsonVariant>();
_statefulService->updateWithoutPropagation(jsonObject, _stateUpdater);
settingsFile.close();
return;
}
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();
}
@@ -64,13 +44,10 @@ class FSPersistence {
mkdirs();
File file = _fs->open(_filePath, "w");
std::string content;
serializeJson(jsonDocument, content);
if (!file) return false;
serializeJson(jsonDocument, file);
file.close();
return true;
return FileSystem::writeFile(_filePath, content.c_str());
}
void disableUpdateHandler() {
@@ -90,26 +67,23 @@ class FSPersistence {
JsonStateReader<T> _stateReader;
JsonStateUpdater<T> _stateUpdater;
StatefulService<T> *_statefulService;
FS *_fs {&ESP_FS};
const char *_filePath;
size_t _bufferSize;
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>();
@@ -117,4 +91,4 @@ class FSPersistence {
}
};
#endif // end FSPersistence
#endif
@@ -1,6 +1,5 @@
#pragma once
#include <Arduino.h>
#include <ArduinoJson.h>
#include <list>
+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];
};
+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;
};
+126
View File
@@ -0,0 +1,126 @@
#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/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;
+11 -5
View File
@@ -1,8 +1,8 @@
#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>
@@ -12,11 +12,17 @@
#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);
static void getNetworks(JsonObject &root);
static void getNetworkStatus(JsonObject &root);
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;
+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(
+28
View File
@@ -0,0 +1,28 @@
# HTTP Server WebSocket support
CONFIG_HTTPD_WS_SUPPORT=y
CONFIG_HTTPD_MAX_REQ_HDR_LEN=1024
CONFIG_HTTPD_MAX_URI_LEN=512
# mDNS
CONFIG_MDNS_MAX_SERVICES=10
# LittleFS
CONFIG_LITTLEFS_MAX_PARTITIONS=3
# 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
+26
View File
@@ -0,0 +1,26 @@
idf_component_register(
SRC_DIRS
"."
"communication"
"peripherals"
"wifi"
"platform_shared"
"../../submodules/nanopb"
INCLUDE_DIRS
"../include"
"../../submodules/nanopb"
REQUIRES
driver
esp_http_server
nvs_flash
esp_wifi
esp_event
esp_netif
mdns
esp_timer
esp_psram
spi_flash
littlefs
esp32-camera
esp-dsp
)
+31 -12
View File
@@ -10,15 +10,38 @@ APService::APService()
_persistence(APSettings_read, APSettings_update, this,
AP_SETTINGS_FILE, api_APSettings_fields, api_APSettings_size,
APSettings_defaults()) {
: endpoint(APSettings::read, APSettings::update, this),
_persistence(APSettings::read, APSettings::update, this, AP_SETTINGS_FILE),
_dnsServer(nullptr),
_lastManaged(0),
_reconfigureAp(false),
_recoveryMode(false) {
addUpdateHandler([&](const std::string &originId) { reconfigureAP(); }, false);
}
APService::~APService() {}
APService::~APService() {
if (_dnsServer) {
delete _dnsServer;
_dnsServer = nullptr;
}
}
void APService::begin() {
_persistence.readFromFS();
}
void APService::status(JsonObject &root) {
root["status"] = getAPNetworkStatus();
root["ip_address"] = (uint32_t)(WiFi.softAPIP());
root["mac_address"] = WiFi.softAPmacAddress().c_str();
root["station_num"] = WiFi.softAPgetStationNum();
}
APNetworkStatus APService::getAPNetworkStatus() {
wifi_mode_t currentWiFiMode = WiFi.getMode();
bool apActive = currentWiFiMode == WIFI_MODE_AP || currentWiFiMode == WIFI_MODE_APSTA;
if (apActive && state().provisionMode != AP_MODE_ALWAYS && WiFi.status() == WL_CONNECTED) {
return APNetworkStatus::LINGERING;
esp_err_t APService::getStatusProto(httpd_req_t *request) {
api_Response res = api_Response_init_zero;
res.status_code = 200;
@@ -64,13 +87,13 @@ void APService::loop() {
}
void APService::manageAP() {
WiFiMode_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) {
wifi_mode_t currentWiFiMode = WiFi.getMode();
if (state().provisionMode == AP_MODE_ALWAYS ||
(state().provisionMode == AP_MODE_DISCONNECTED && WiFi.status() != WL_CONNECTED) || _recoveryMode) {
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 +105,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 +126,4 @@ void APService::stopAP() {
WiFi.softAPdisconnect(true);
}
void APService::handleDNS() {
if (_dnsServer) {
_dnsServer->processNextRequest();
}
}
void APService::handleDNS() {}
+164 -22
View File
@@ -3,8 +3,9 @@
#include <vector>
#include <cstring>
#include "utils/string_utils.hpp"
#include <esp_log.h>
static const char *TAG = "FileService";
static const char *TAG = "FileSystem";
namespace FileSystem {
@@ -88,23 +89,127 @@ esp_err_t getFilesProto(httpd_req_t *request) {
freeAllocatedEntries(); // Clean up after sending
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 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();
@@ -128,6 +233,18 @@ esp_err_t handleDelete(httpd_req_t *request, const api_FileDeleteRequest &req) {
return WebServer::send(request, 200, res, api_Response_fields);
} else {
return WebServer::sendError(request, 500, "Delete failed");
httpd_resp_set_type(request, "application/json");
return httpd_resp_send(request, content.c_str(), content.length());
}
esp_err_t handleDelete(httpd_req_t *request, JsonVariant &json) {
if (json.is<JsonObject>()) {
const char *filename = json["file"].as<const char *>();
std::string fullPath = std::string(MOUNT_POINT) + filename;
ESP_LOGI(TAG, "Deleting file: %s", fullPath.c_str());
return deleteFile(fullPath.c_str()) ? WebServer::sendOk(request)
: WebServer::sendError(request, 500, "Delete failed");
}
}
@@ -141,35 +258,52 @@ esp_err_t handleEdit(httpd_req_t *request, const api_FileEditRequest &req) {
return WebServer::send(request, 200, res, api_Response_fields);
} else {
return WebServer::sendError(request, 500, "Edit failed");
esp_err_t handleEdit(httpd_req_t *request, JsonVariant &json) {
if (json.is<JsonObject>()) {
const char *filename = json["file"].as<const char *>();
const char *content = json["content"].as<const char *>();
std::string fullPath = std::string(MOUNT_POINT) + filename;
ESP_LOGI(TAG, "Editing file: %s", fullPath.c_str());
return editFile(fullPath.c_str(), content) ? WebServer::sendOk(request)
: WebServer::sendError(request, 500, "Edit failed");
}
}
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 += "}";
@@ -196,6 +330,14 @@ esp_err_t mkdir(httpd_req_t *request, const api_FileMkdirRequest &req) {
} else {
return WebServer::sendError(request, 500, "mkdir failed");
}
bool editFile(const char *filename, const char *content) { return writeFile(filename, content); }
esp_err_t mkdir(httpd_req_t *request, JsonVariant &json) {
const char *path = json["path"].as<const char *>();
std::string fullPath = std::string(MOUNT_POINT) + path;
ESP_LOGI(TAG, "Creating directory: %s", fullPath.c_str());
return mkdirRecursive(fullPath.c_str()) ? WebServer::sendOk(request)
: WebServer::sendError(request, 500, "mkdir failed");
}
} // namespace FileSystem
+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
+18
View File
@@ -0,0 +1,18 @@
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"
+46 -34
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>
@@ -20,7 +23,7 @@
#include <www_mount.hpp>
Websocket socket {server, "/api/ws"};
Websocket wsSocket {server, "/api/ws"};
Peripherals peripherals;
ServoController servoController;
@@ -123,35 +126,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 +228,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 +238,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 +251,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());
@@ -272,8 +278,9 @@ void IRAM_ATTR serviceLoopEntry(void *) {
ESP_LOGI("main", "Service task starting");
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)
@@ -282,7 +289,7 @@ void IRAM_ATTR serviceLoopEntry(void *) {
setupServer();
socket.begin();
wsSocket.begin();
setupEventSocket();
ESP_LOGI("main", "Service task started");
@@ -291,23 +298,23 @@ void IRAM_ATTR serviceLoopEntry(void *) {
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);
}
});
@@ -317,18 +324,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); }
+88 -2
View File
@@ -1,5 +1,6 @@
#include <mdns_service.h>
#include <communication/webserver.h>
#include <esp_netif.h>
static const char *TAG = "MDNSService";
@@ -42,14 +43,35 @@ void MDNSService::startMDNS() {
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.c_str());
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.c_str());
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.c_str());
}
void MDNSService::stopMDNS() {
ESP_LOGV(TAG, "Stopping MDNS");
MDNS.end();
mdns_free();
_started = false;
}
@@ -69,6 +91,24 @@ void MDNSService::addServices() {
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);
for (const auto &service : state().services) {
esp_err_t err =
mdns_service_add(nullptr, service.service.c_str(), service.protocol.c_str(), service.port, nullptr, 0);
if (err != ESP_OK) {
ESP_LOGW(TAG, "Failed to add service %s: %s", service.service.c_str(), esp_err_to_name(err));
continue;
}
for (const auto &txt : service.txtRecords) {
mdns_service_txt_item_set(service.service.c_str(), service.protocol.c_str(), txt.key.c_str(),
txt.value.c_str());
}
}
for (const auto &txt : state().globalTxtRecords) {
for (const auto &service : state().services) {
mdns_service_txt_item_set(service.service.c_str(), service.protocol.c_str(), txt.key.c_str(),
txt.value.c_str());
}
}
}
@@ -121,4 +161,50 @@ esp_err_t MDNSService::queryServices(httpd_req_t *request, api_Request *protoReq
}
return WebServer::send(request, 200, response, api_Response_fields);
esp_err_t MDNSService::queryServices(httpd_req_t *request, JsonVariant &json) {
std::string service = json["service"].as<std::string>();
std::string proto = json["protocol"].as<std::string>();
JsonDocument doc;
JsonVariant root = doc.to<JsonVariant>();
ESP_LOGI(TAG, "Querying for service: %s, protocol: %s", service.c_str(), proto.c_str());
mdns_result_t *results = nullptr;
esp_err_t err = mdns_query_ptr(service.c_str(), proto.c_str(), 3000, 20, &results);
if (err != ESP_OK) {
ESP_LOGW(TAG, "MDNS query failed: %s", esp_err_to_name(err));
root["services"] = JsonArray();
return WebServer::sendJson(request, 200, doc);
}
int count = 0;
mdns_result_t *r = results;
while (r) {
count++;
r = r->next;
}
ESP_LOGI(TAG, "Found %d services", count);
JsonArray servicesArray = root["services"].to<JsonArray>();
r = results;
while (r) {
JsonVariant serviceObj = servicesArray.add<JsonVariant>();
if (r->hostname) {
serviceObj["name"] = r->hostname;
}
if (r->addr) {
char ip_str[16];
esp_ip4addr_ntoa(&r->addr->addr.u_addr.ip4, ip_str, sizeof(ip_str));
serviceObj["ip"] = ip_str;
}
serviceObj["port"] = r->port;
r = r->next;
}
mdns_query_results_free(results);
return WebServer::sendJson(request, 200, doc);
}
+3 -2
View File
@@ -1,5 +1,6 @@
#include <peripherals/camera_service.h>
#include <communication/webserver.h>
#include <esp_heap_caps.h>
namespace Camera {
@@ -66,7 +67,7 @@ esp_err_t CameraService::begin() {
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 +79,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");
+131 -19
View File
@@ -1,5 +1,39 @@
#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_ESP32 || CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
#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 = TEMPERATURE_SENSOR_CONFIG_DEFAULT(-10, 80);
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 +56,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 +74,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,7 +89,7 @@ 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);
@@ -72,22 +109,97 @@ 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";
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());
}
+569
View File
@@ -0,0 +1,569 @@
#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);
}
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);
}
_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; }
+74 -24
View File
@@ -1,42 +1,47 @@
#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,
API_REQUEST_EXTRACTOR(wifi_settings, api_WifiSettings),
API_RESPONSE_ASSIGNER(wifi_settings, api_WifiSettings)) {
: _persistence(WiFiSettings::read, WiFiSettings::update, this, WIFI_SETTINGS_FILE),
_lastConnectionAttempt(0),
_stopping(false),
endpoint(WiFiSettings::read, WiFiSettings::update, this) {
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().wifiSettings.empty()) {
WiFi.mode(WIFI_MODE_STA);
vTaskDelay(100 / portTICK_PERIOD_MS);
configureNetwork(state().wifiSettings[0]);
}
}
void WiFiService::reconfigureWiFiConnection() {
_lastConnectionAttempt = 0;
if (WiFi.disconnect(true)) _stopping = true;
}
@@ -97,6 +102,28 @@ void WiFiService::setupMDNS(const char *hostname) {
MDNS.addServiceTxt("http", "tcp", "Firmware Version", APP_VERSION);
}
mdns_init();
mdns_hostname_set(state().hostname.c_str());
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);
}
void WiFiService::getNetworks(JsonObject &root) {
JsonArray networks = root["networks"].to<JsonArray>();
int numNetworks = WiFi.scanComplete();
for (int i = 0; i < numNetworks; i++) {
JsonObject network = networks.add<JsonObject>();
network["rssi"] = WiFi.RSSI(i);
network["ssid"] = WiFi.SSID(i).c_str();
network["bssid"] = WiFi.BSSIDstr(i).c_str();
network["channel"] = WiFi.channel(i);
network["encryption_type"] = (uint8_t)WiFi.encryptionType(i);
}
}
esp_err_t WiFiService::getNetworkStatus(httpd_req_t *request) {
api_Response response = api_Response_init_zero;
response.which_payload = api_Response_wifi_status_tag;
@@ -115,6 +142,14 @@ esp_err_t WiFiService::getNetworkStatus(httpd_req_t *request) {
wifiStatus.subnet_mask = static_cast<uint32_t>(WiFi.subnetMask());
wifiStatus.gateway_ip = static_cast<uint32_t>(WiFi.gatewayIP());
root["local_ip"] = (uint32_t)(WiFi.localIP());
root["mac_address"] = WiFi.macAddress().c_str();
root["rssi"] = WiFi.RSSI();
root["ssid"] = WiFi.SSID().c_str();
root["bssid"] = WiFi.BSSIDstr().c_str();
root["channel"] = WiFi.channel();
root["subnet_mask"] = (uint32_t)(WiFi.subnetMask());
root["gateway_ip"] = (uint32_t)(WiFi.gatewayIP());
IPAddress dnsIP1 = WiFi.dnsIP(0);
IPAddress dnsIP2 = WiFi.dnsIP(1);
if (dnsIP1 != IPAddress(0, 0, 0, 0)) {
@@ -131,22 +166,24 @@ 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();
if (WiFi.isConnected() || state().wifiSettings.empty()) return;
connectToWiFi();
}
void WiFiService::connectToWiFi() {
int scanResult = WiFi.scanNetworks();
if (scanResult == WIFI_SCAN_FAILED) {
ESP_LOGE("WiFiSettingsService", "WiFi scan failed.");
if (scanResult < 0) {
ESP_LOGE(TAG, "WiFi scan failed.");
} else if (scanResult == 0) {
ESP_LOGI("WiFiSettingsService", "No networks found.");
ESP_LOGI(TAG, "No networks found.");
} else {
ESP_LOGI("WiFiSettingsService", "%d networks found.", scanResult);
ESP_LOGI(TAG, "%d networks found.", scanResult);
WiFiNetwork *bestNetwork = nullptr;
int32_t bestNetworkDb = FACTORY_WIFI_RSSI_THRESHOLD;
for (int i = 0; i < scanResult; ++i) {
String ssid_scan;
std::string ssid_scan;
int32_t rssi_scan;
uint8_t sec_scan;
uint8_t *BSSID_scan;
@@ -156,6 +193,7 @@ void WiFiService::connectToWiFi() {
for (pb_size_t j = 0; j < state().wifi_networks_count; j++) {
WiFiNetwork &network = state().wifi_networks[j];
for (auto &network : state().wifiSettings) {
if (ssid_scan == network.ssid) {
if (rssi_scan >= FACTORY_WIFI_RSSI_THRESHOLD) {
// Network is available
@@ -183,9 +221,19 @@ void WiFiService::connectToWiFi() {
}
} else if (bestNetwork) {
ESP_LOGI("WiFiSettingsService", "Connecting to strongest network: %s", bestNetwork->ssid);
if (!state().priorityBySignalStrength) {
for (auto &network : state().wifiSettings) {
if (network.available == true) {
ESP_LOGI(TAG, "Connecting to first available network: %s", network.ssid.c_str());
configureNetwork(network);
break;
}
}
} else if (state().priorityBySignalStrength && bestNetwork) {
ESP_LOGI(TAG, "Connecting to strongest network: %s", bestNetwork->ssid.c_str());
configureNetwork(*bestNetwork);
} else {
ESP_LOGI("WiFiSettingsService", "No known networks found.");
ESP_LOGI(TAG, "No known networks found.");
}
WiFi.scanDelete();
@@ -202,26 +250,28 @@ void WiFiService::configureNetwork(WiFiNetwork &network) {
WiFi.setHostname(state().hostname);
WiFi.begin(network.ssid, network.password);
WiFi.setHostname(state().hostname.c_str());
WiFi.begin(network.ssid.c_str(), network.password.c_str());
#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());
}
+2 -2
View File
@@ -7,11 +7,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);
+11 -10
View File
@@ -40,14 +40,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
@@ -80,7 +79,7 @@ build_flags =
[env]
platform = espressif32 @ 6.8.1
framework = arduino
framework = espidf
monitor_speed = 115200
monitor_filters =
esp32_exception_decoder
@@ -98,21 +97,23 @@ 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
bblanchon/ArduinoJson@^7.0.0
lib_ldf_mode = deep
lib_compat_mode = off
extra_scripts =
pre:esp32/scripts/pre_build.py
pre:esp32/scripts/build_app.py