Skip to content

Commit

Permalink
Upgrade to arduino-esp32 v3.0.0
Browse files Browse the repository at this point in the history
  • Loading branch information
mskvortsov committed May 27, 2024
1 parent 77cf5c6 commit 27acc2e
Show file tree
Hide file tree
Showing 29 changed files with 189 additions and 93 deletions.
14 changes: 10 additions & 4 deletions arch/esp32/esp32.ini
Original file line number Diff line number Diff line change
@@ -1,7 +1,13 @@
; Common settings for ESP targes, mixin with extends = esp32_base
[esp32_base]
extends = arduino_base
platform = platformio/[email protected]
platform = https://github.com/platformio/platform-espressif32.git
platform_packages =
framework-arduinoespressif32@https://github.com/espressif/arduino-esp32#3.0.0-rc3
platformio/framework-arduinoespressif32-libs@https://github.com/espressif/esp32-arduino-libs.git#9a202d7075a535ab8f563ed7cdb9960a6d3e3f80
espressif/toolchain-riscv32-esp@^12.2.0
espressif/toolchain-xtensa-esp32s3@^12.2.0
espressif/toolchain-xtensa-esp32@^12.2.0

build_src_filter =
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2040> -<mesh/eth/> -<mesh/raspihttp>
Expand All @@ -18,7 +24,7 @@ board_build.filesystem = littlefs
build_unflags = -fno-lto
build_flags =
${arduino_base.build_flags}
-flto
-flto=auto
-Wall
-Wextra
-Isrc/platform/esp32
Expand All @@ -31,18 +37,18 @@ build_flags =
-DCONFIG_NIMBLE_CPP_LOG_LEVEL=2
-DCONFIG_BT_NIMBLE_MAX_CCCDS=20
-DCONFIG_BT_NIMBLE_HOST_TASK_STACK_SIZE=5120
-DESP_OPENSSL_SUPPRESS_LEGACY_WARNING
-DSERIAL_BUFFER_SIZE=4096
-DLIBPAX_ARDUINO
-DLIBPAX_WIFI
-DLIBPAX_BLE
;-DDEBUG_HEAP
-include src/platform/esp32/quirks.h

lib_deps =
${arduino_base.lib_deps}
${networking_base.lib_deps}
${environmental_base.lib_deps}
https://github.com/meshtastic/esp32_https_server.git#23665b3adc080a311dcbb586ed5941b5f94d6ea2
https://github.com/mskvortsov/esp32_https_server.git#mbedtls
h2zero/NimBLE-Arduino@^1.4.1
https://github.com/dbSuS/libpax.git#7bcd3fcab75037505be9b122ab2b24cc5176b587
https://github.com/lewisxhe/XPowersLib.git#84b7373faea3118b6c37954d52f98b8a337148d6
Expand Down
13 changes: 13 additions & 0 deletions bin/platformio-custom.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,19 @@ def esp32_create_combined_bin(source, target, env):
env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", esp32_create_combined_bin)
env.Append(LINKFLAGS=["--specs=nano.specs", "-u", "_printf_float"])

# XXX
for lb in env.GetLibBuilders():
if lb.name == "NonBlockingRTTTL":
lb.env.Append(CPPDEFINES=[("QUIRK_RTTTL", 1)])
elif lb.name == "LovyanGFX":
lb.env.Append(CPPDEFINES=[("QUIRK_LOVYAN", 1)])
elif lb.name == "ESP8266Audio":
lb.env.Append(CPPDEFINES=[("QUIRK_ESP8266_AUDIO", 1)])
framework_path = env.PioPlatform().get_package_dir(
"framework-arduinoespressif32"
)
lb.env.Append(CXXFLAGS=["-I" + framework_path + "/libraries/WiFi/src"])

Import("projenv")

prefsLoc = projenv["PROJECT_DIR"] + "/version.properties"
Expand Down
8 changes: 4 additions & 4 deletions src/OSTimer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,18 +42,18 @@ static void IRAM_ATTR onTimer()
bool scheduleHWCallback(PendableFunction callback, void *param1, uint32_t param2, uint32_t delayMsec)
{
if (!timer) {
timer = timerBegin(0, 80, true); // one usec per tick (main clock is 80MhZ on ESP32)
timer = timerBegin(80); // one usec per tick (main clock is 80MhZ on ESP32)
assert(timer);
timerAttachInterrupt(timer, &onTimer, true);
timerAttachInterrupt(timer, &onTimer);
}

tCallback = callback;
tParam1 = param1;
tParam2 = param2;

timerAlarmWrite(timer, delayMsec * 1000UL, false); // Do not reload, we want it to be a single shot timer
timerAlarm(timer, delayMsec * 1000UL, false, 0); // Do not reload, we want it to be a single shot timer
timerRestart(timer);
timerAlarmEnable(timer);
timerStart(timer);
return true;
}

Expand Down
107 changes: 65 additions & 42 deletions src/Power.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,17 +38,17 @@

#if defined(BATTERY_PIN) && defined(ARCH_ESP32)

static adc_channel_t adc_channel;
#ifndef BAT_MEASURE_ADC_UNIT // ADC1 is default
static const adc1_channel_t adc_channel = ADC_CHANNEL;
static const adc_unit_t unit = ADC_UNIT_1;
static adc_unit_t unit = ADC_UNIT_1;
#else // ADC2
static const adc2_channel_t adc_channel = ADC_CHANNEL;
static const adc_unit_t unit = ADC_UNIT_2;
static adc_unit_t unit = ADC_UNIT_2;
RTC_NOINIT_ATTR uint64_t RTC_reg_b;

#endif // BAT_MEASURE_ADC_UNIT

esp_adc_cal_characteristics_t *adc_characs = (esp_adc_cal_characteristics_t *)calloc(1, sizeof(esp_adc_cal_characteristics_t));
static adc_oneshot_unit_handle_t adc_unit_handle;
static adc_cali_handle_t adc_cali_handle;
#ifndef ADC_ATTENUATION
static const adc_atten_t atten = ADC_ATTEN_DB_12;
#else
Expand Down Expand Up @@ -214,8 +214,9 @@ class AnalogBatteryLevel : public HasBatteryLevel

#ifdef ARCH_ESP32 // ADC block for espressif platforms
raw = espAdcRead();
scaled = esp_adc_cal_raw_to_voltage(raw, adc_characs);
scaled *= operativeAdcMultiplier;
int millivolts = 0;
adc_cali_raw_to_voltage(adc_cali_handle, raw, &millivolts); // TODO check result
scaled = millivolts * operativeAdcMultiplier;
#else // block for all other platforms
for (uint32_t i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
raw += analogRead(BATTERY_PIN);
Expand Down Expand Up @@ -258,9 +259,11 @@ class AnalogBatteryLevel : public HasBatteryLevel
digitalWrite(ADC_CTRL, ADC_CTRL_ENABLED);
delay(10);
#endif

int val_;
for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
int val_ = adc1_get_raw(adc_channel);
if (val_ >= 0) { // save only valid readings
esp_err_t res = adc_oneshot_read(adc_unit_handle, adc_channel, &val_);
if (res == ESP_OK) { // save only valid readings
raw += val_;
raw_c++;
}
Expand All @@ -282,15 +285,15 @@ class AnalogBatteryLevel : public HasBatteryLevel
// ADC2 wifi bug workaround not required, breaks compile
// On ESP32S3, ADC2 can take turns with Wifi (?)

int32_t adc_buf;
int adc_buf;
esp_err_t read_result;

// Multiple samples
for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
adc_buf = 0;
read_result = -1;

read_result = adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf);
read_result = adc_oneshot_read(adc_unit_handle, adc_channel, &adc_buf);
if (read_result == ESP_OK) {
raw += adc_buf;
raw_c++; // Count valid samples
Expand All @@ -300,15 +303,17 @@ class AnalogBatteryLevel : public HasBatteryLevel
}

#else // Other ESP32
int32_t adc_buf = 0;
int adc_buf = 0;
for (int i = 0; i < BATTERY_SENSE_SAMPLES; i++) {
// ADC2 wifi bug workaround, see
// https://github.com/espressif/arduino-esp32/issues/102
WRITE_PERI_REG(SENS_SAR_READ_CTRL2_REG, RTC_reg_b);
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV);
adc2_get_raw(adc_channel, ADC_WIDTH_BIT_12, &adc_buf);
raw += adc_buf;
raw_c++;
esp_err_t res = adc_oneshot_read(adc_unit_handle, adc_channel, &adc_buf);
if (res == ESP_OK) { // save only valid readings
raw += adc_buf;
raw_c++;
}
}
#endif // BAT_MEASURE_ADC_UNIT

Expand Down Expand Up @@ -438,47 +443,65 @@ bool Power::analogInit()
#endif

#ifdef ARCH_ESP32 // ESP32 needs special analog stuff

#ifndef ADC_WIDTH // max resolution by default
static const adc_bits_width_t width = ADC_WIDTH_BIT_12;
adc_oneshot_io_to_channel(ADC_CHANNEL, &unit, &adc_channel);
adc_oneshot_unit_init_cfg_t adc_unit_config = {
.unit_id = unit,
};
adc_oneshot_new_unit(&adc_unit_config, &adc_unit_handle); // TODO check result
#ifndef ADC_WIDTH // max resolution by default
static const adc_bitwidth_t width = ADC_BITWIDTH_12;
#else
static const adc_bits_width_t width = ADC_WIDTH;
#endif
#ifndef BAT_MEASURE_ADC_UNIT // ADC1
adc1_config_width(width);
adc1_config_channel_atten(adc_channel, atten);
#else // ADC2
adc2_config_channel_atten(adc_channel, atten);
#ifndef CONFIG_IDF_TARGET_ESP32S3
static const adc_bitwidth_t width = ADC_WIDTH;
#endif
adc_oneshot_chan_cfg_t chan_config = {
.atten = atten,
.bitwidth = width,
};
adc_oneshot_config_channel(adc_unit_handle, adc_channel, &chan_config); // TODO check result
#if defined(BAT_MEASURE_ADC_UNIT) && !defined(CONFIG_IDF_TARGET_ESP32S3)
// ADC2 wifi bug workaround
// Not required with ESP32S3, breaks compile
RTC_reg_b = READ_PERI_REG(SENS_SAR_READ_CTRL2_REG);
#endif
#endif
// calibrate ADC
esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, width, DEFAULT_VREF, adc_characs);

#if ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED
adc_cali_line_fitting_config_t cali_config = {
.unit_id = unit,
.atten = atten,
.bitwidth = ADC_BITWIDTH_DEFAULT,
.default_vref = DEFAULT_VREF,
};
adc_cali_create_scheme_line_fitting(&cali_config, &adc_cali_handle);
adc_cali_line_fitting_efuse_val_t val_type;
adc_cali_scheme_line_fitting_check_efuse(&val_type);
// show ADC characterization base
if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP) {
LOG_INFO("ADCmod: ADC characterization based on Two Point values stored in eFuse\n");
} else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) {
switch (val_type) {
case ADC_CALI_LINE_FITTING_EFUSE_VAL_EFUSE_VREF:
LOG_INFO("ADCmod: ADC characterization based on reference voltage stored in eFuse\n");
}
#ifdef CONFIG_IDF_TARGET_ESP32S3
// ESP32S3
else if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP_FIT) {
LOG_INFO("ADCmod: ADC Characterization based on Two Point values and fitting curve coefficients stored in eFuse\n");
}
#endif
else {
break;
case ADC_CALI_LINE_FITTING_EFUSE_VAL_EFUSE_TP:
LOG_INFO("ADCmod: ADC characterization based on Two Point values stored in eFuse\n");
break;
case ADC_CALI_LINE_FITTING_EFUSE_VAL_DEFAULT_VREF:
LOG_INFO("ADCmod: ADC characterization based on default reference voltage\n");
break;
}
#else
adc_cali_curve_fitting_config_t cali_config = {
.unit_id = unit,
.chan = adc_channel,
.atten = atten,
.bitwidth = ADC_BITWIDTH_DEFAULT,
};
adc_cali_create_scheme_curve_fitting(&cali_config, &adc_cali_handle); // TODO check result
#endif
#endif // ARCH_ESP32

#ifdef ARCH_NRF52
#ifdef VBAT_AR_INTERNAL
analogReference(VBAT_AR_INTERNAL);
#else
analogReference(AR_INTERNAL); // 3.6V
analogReference(AR_INTERNAL); // 3.6V
#endif
#endif // ARCH_NRF52

Expand Down Expand Up @@ -993,4 +1016,4 @@ bool Power::axpChipInit()
#else
return false;
#endif
}
}
2 changes: 1 addition & 1 deletion src/gps/GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ int GPS::getACK(uint8_t *buffer, uint16_t size, uint8_t requestedClass, uint8_t
{
uint16_t ubxFrameCounter = 0;
uint32_t startTime = millis();
uint16_t needRead;
uint16_t needRead = 0;

while (millis() - startTime < waitMillis) {
if (_serial_gps->available()) {
Expand Down
3 changes: 2 additions & 1 deletion src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
// #include <driver/rtc_io.h>

#ifdef ARCH_ESP32
#include "driver/gpio.h"
#if !MESHTASTIC_EXCLUDE_WEBSERVER
#include "mesh/http/WebServer.h"
#endif
Expand Down Expand Up @@ -170,7 +171,7 @@ const char *getDeviceName()
static char name[20];
snprintf(name, sizeof(name), "%02x%02x", dmac[4], dmac[5]);
// if the shortname exists and is NOT the new default of ab3c, use it for BLE name.
if ((owner.short_name != NULL) && (strcmp(owner.short_name, name) != 0)) {
if (strcmp(owner.short_name, name) != 0) {
snprintf(name, sizeof(name), "%s_%02x%02x", owner.short_name, dmac[4], dmac[5]);
} else {
snprintf(name, sizeof(name), "Meshtastic_%02x%02x", dmac[4], dmac[5]);
Expand Down
7 changes: 2 additions & 5 deletions src/mesh/NodeDB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
#include "modules/esp32/StoreForwardModule.h"
#include <Preferences.h>
#include <nvs_flash.h>
#undef EXT_RAM_ATTR
#define EXT_RAM_ATTR EXT_RAM_BSS_ATTR
#endif

#ifdef ARCH_PORTDUINO
Expand Down Expand Up @@ -141,11 +143,6 @@ NodeDB::NodeDB()
if (channelFileCRC != crc32Buffer(&channelFile, sizeof(channelFile)))
saveWhat |= SEGMENT_CHANNELS;

if (!devicestate.node_remote_hardware_pins) {
meshtastic_NodeRemoteHardwarePin empty[12] = {meshtastic_RemoteHardwarePin_init_default};
memcpy(devicestate.node_remote_hardware_pins, empty, sizeof(empty));
}

if (config.position.gps_enabled) {
config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED;
config.position.gps_enabled = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/mesh/TypedQueue.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
*/
template <class T> class TypedQueue
{
static_assert(std::is_pod<T>::value, "T must be pod");
static_assert(std::is_standard_layout<T>::value && std::is_trivial<T>::value, "T must be pod");
QueueHandle_t h;
concurrency::OSThread *reader = NULL;

Expand Down Expand Up @@ -112,4 +112,4 @@ template <class T> class TypedQueue

void setReader(concurrency::OSThread *t) { reader = t; }
};
#endif
#endif
6 changes: 5 additions & 1 deletion src/mesh/api/ServerAPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,11 @@ template <class T, class U> void APIServerPort<T, U>::init()

template <class T, class U> int32_t APIServerPort<T, U>::runOnce()
{
#ifdef ARCH_ESP32
auto client = U::accept();
#else
auto client = U::available();
#endif
if (client) {
// Close any previous connection (see FIXME in header file)
if (openAPI) {
Expand All @@ -57,4 +61,4 @@ template <class T, class U> int32_t APIServerPort<T, U>::runOnce()
}

return 100; // only check occasionally for incoming connections
}
}
3 changes: 2 additions & 1 deletion src/mesh/http/ContentHelper.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include <Arduino.h>
#include <functional>
#include <string>

#define BoolToString(x) ((x) ? "true" : "false")

void replaceAll(std::string &str, const std::string &from, const std::string &to);
void replaceAll(std::string &str, const std::string &from, const std::string &to);
3 changes: 2 additions & 1 deletion src/mesh/wifi/WiFiAPClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,8 @@ static void WiFiEvent(WiFiEvent_t event)
onNetworkConnected();
break;
case ARDUINO_EVENT_WIFI_STA_GOT_IP6:
LOG_INFO("Obtained IP6 address: %s\n", WiFi.localIPv6().toString().c_str());
LOG_INFO("Obtained link-local IP6 address: %s\n", WiFi.linkLocalIPv6().toString().c_str());
LOG_INFO("Obtained global IP6 address: %s\n", WiFi.globalIPv6().toString().c_str());
break;
case ARDUINO_EVENT_WIFI_STA_LOST_IP:
LOG_INFO("Lost IP address and IP address is reset to 0\n");
Expand Down
3 changes: 1 addition & 2 deletions src/modules/AdminModule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,8 +293,7 @@ bool AdminModule::handleReceivedProtobuf(const meshtastic_MeshPacket &mp, meshta
void AdminModule::handleGetModuleConfigResponse(const meshtastic_MeshPacket &mp, meshtastic_AdminMessage *r)
{
// Skip if it's disabled or no pins are exposed
if (!r->get_module_config_response.payload_variant.remote_hardware.enabled ||
!r->get_module_config_response.payload_variant.remote_hardware.available_pins) {
if (!r->get_module_config_response.payload_variant.remote_hardware.enabled) {
LOG_DEBUG("Remote hardware module disabled or no vailable_pins. Skipping...\n");
return;
}
Expand Down
Loading

0 comments on commit 27acc2e

Please sign in to comment.