diff --git a/boards.txt b/boards.txt index 03b8a34b58c..28d6b4d897c 100644 --- a/boards.txt +++ b/boards.txt @@ -18,6 +18,7 @@ menu.MemoryType=Memory Type menu.EraseFlash=Erase All Flash Before Sketch Upload menu.JTAGAdapter=JTAG Adapter menu.ZigbeeMode=Zigbee Mode +menu.PinNumbers=Pin Numbering # Custom options menu.Revision=Board Revision @@ -29688,4 +29689,72 @@ sensebox_mcu_esp32s2.menu.EraseFlash.none.upload.erase_cmd= sensebox_mcu_esp32s2.menu.EraseFlash.all=Enabled sensebox_mcu_esp32s2.menu.EraseFlash.all.upload.erase_cmd=-e -############################################################## \ No newline at end of file +############################################################## + +nano_nora.name=Arduino Nano ESP32 +nano_nora.vid.0=0x2341 +nano_nora.pid.0=0x0070 +nano_nora.upload_port.0.vid=0x2341 +nano_nora.upload_port.0.pid=0x0070 + +nano_nora.bootloader.tool=esptool_py +nano_nora.bootloader.tool.default=esptool_py + +nano_nora.upload.tool=dfu-util +nano_nora.upload.tool.default=dfu-util +nano_nora.upload.tool.network=esp_ota +nano_nora.upload.protocol=serial +nano_nora.upload.maximum_size=3145728 +nano_nora.upload.maximum_data_size=327680 +nano_nora.upload.use_1200bps_touch=false +nano_nora.upload.wait_for_upload_port=false + +nano_nora.serial.disableDTR=false +nano_nora.serial.disableRTS=false + +nano_nora.build.tarch=xtensa +nano_nora.build.bootloader_addr=0x0 +nano_nora.build.target=esp32s3 +nano_nora.build.mcu=esp32s3 +nano_nora.build.core=esp32 +nano_nora.build.variant=arduino_nano_nora +nano_nora.build.board=NANO_ESP32 +nano_nora.build.code_debug=0 + +nano_nora.build.usb_mode=0 +nano_nora.build.cdc_on_boot=1 +nano_nora.build.msc_on_boot=0 +nano_nora.build.dfu_on_boot=1 +nano_nora.build.f_cpu=240000000L +nano_nora.build.flash_size=16MB +nano_nora.build.flash_freq=80m +nano_nora.build.flash_mode=dio +nano_nora.build.boot=qio +nano_nora.build.boot_freq=80m +nano_nora.build.partitions=app3M_fat9M_fact512k_16MB +nano_nora.build.defines=-DBOARD_HAS_PIN_REMAP {build.disable_pin_remap} -DBOARD_HAS_PSRAM '-DUSB_MANUFACTURER="Arduino"' '-DUSB_PRODUCT="Nano ESP32"' +nano_nora.build.loop_core=-DARDUINO_RUNNING_CORE=1 +nano_nora.build.event_core=-DARDUINO_EVENT_RUNNING_CORE=1 +nano_nora.build.psram_type=opi +nano_nora.build.memory_type={build.boot}_{build.psram_type} +nano_nora.build.disable_pin_remap= + +nano_nora.tools.esptool_py.program.pattern_args=--chip {build.mcu} --port "{serial.port}" --before default_reset --after hard_reset write_flash -z --flash_mode {build.flash_mode} --flash_freq {build.flash_freq} --flash_size {build.flash_size} {build.bootloader_addr} "{build.path}/{build.project_name}.bootloader.bin" 0x8000 "{build.path}/{build.project_name}.partitions.bin" 0xe000 "{runtime.platform.path}/tools/partitions/boot_app0.bin" 0xf70000 "{build.variant.path}/extra/nora_recovery/nora_recovery.ino.bin" 0x10000 "{build.path}/{build.project_name}.bin" +nano_nora.tools.esptool_py.erase.pattern_args=--chip {build.mcu} --port "{serial.port}" --before default_reset --after hard_reset erase_flash + +nano_nora.menu.PartitionScheme.default=With FAT partition (default) +nano_nora.menu.PartitionScheme.spiffs=With SPIFFS partition (advanced) +nano_nora.menu.PartitionScheme.spiffs.build.partitions=app3M_spiffs9M_fact512k_16MB + +nano_nora.menu.PinNumbers.default=By Arduino pin (default) +nano_nora.menu.PinNumbers.byGPIONumber=By GPIO number (legacy) +nano_nora.menu.PinNumbers.byGPIONumber.build.disable_pin_remap=-DBOARD_USES_HW_GPIO_NUMBERS + +nano_nora.menu.USBMode.default=Normal mode (TinyUSB) +nano_nora.menu.USBMode.hwcdc=Debug mode (Hardware CDC) +nano_nora.menu.USBMode.hwcdc.build.usb_mode=1 +nano_nora.menu.USBMode.hwcdc.build.copy_jtag_files=1 +nano_nora.menu.USBMode.hwcdc.build.openocdscript=esp32s3-builtin.cfg +nano_nora.menu.USBMode.hwcdc.build.debugconfig=esp32s3-arduino.json + +############################################################## diff --git a/cores/esp32/Arduino.h b/cores/esp32/Arduino.h index 0b0996885af..b03c34f297f 100644 --- a/cores/esp32/Arduino.h +++ b/cores/esp32/Arduino.h @@ -111,13 +111,13 @@ #define analogInPinToBit(P) (P) #if SOC_GPIO_PIN_COUNT <= 32 #define digitalPinToPort(pin) (0) -#define digitalPinToBitMask(pin) (1UL << (pin)) +#define digitalPinToBitMask(pin) (1UL << digitalPinToGPIONumber(pin)) #define portOutputRegister(port) ((volatile uint32_t*)GPIO_OUT_REG) #define portInputRegister(port) ((volatile uint32_t*)GPIO_IN_REG) #define portModeRegister(port) ((volatile uint32_t*)GPIO_ENABLE_REG) #elif SOC_GPIO_PIN_COUNT <= 64 -#define digitalPinToPort(pin) (((pin)>31)?1:0) -#define digitalPinToBitMask(pin) (1UL << (((pin)>31)?((pin)-32):(pin))) +#define digitalPinToPort(pin) ((digitalPinToGPIONumber(pin)>31)?1:0) +#define digitalPinToBitMask(pin) (1UL << (digitalPinToGPIONumber(pin)&31)) #define portOutputRegister(port) ((volatile uint32_t*)((port)?GPIO_OUT1_REG:GPIO_OUT_REG)) #define portInputRegister(port) ((volatile uint32_t*)((port)?GPIO_IN1_REG:GPIO_IN_REG)) #define portModeRegister(port) ((volatile uint32_t*)((port)?GPIO_ENABLE1_REG:GPIO_ENABLE_REG)) @@ -139,8 +139,8 @@ #endif #define EXTERNAL_NUM_INTERRUPTS NUM_DIGITAL_PINS // All GPIOs #define analogInputToDigitalPin(p) (((p) struct InterruptArgStructure { - std::function interruptFunction; + std::function interruptFunction; }; -void attachInterrupt(uint8_t pin, std::function intRoutine, int mode); - +// The extra set of parentheses here prevents macros defined +// in io_pin_remap.h from applying to this declaration. +void (attachInterrupt)(uint8_t pin, std::function intRoutine, int mode); #endif /* CORE_CORE_FUNCTIONALINTERRUPT_H_ */ diff --git a/cores/esp32/HardwareSerial.cpp b/cores/esp32/HardwareSerial.cpp index fdec193774a..7792b8e039b 100644 --- a/cores/esp32/HardwareSerial.cpp +++ b/cores/esp32/HardwareSerial.cpp @@ -5,6 +5,7 @@ #include #include "pins_arduino.h" +#include "io_pin_remap.h" #include "HardwareSerial.h" #include "soc/soc_caps.h" #include "driver/uart.h" @@ -325,6 +326,10 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in } } + // map logical pins to GPIO numbers + rxPin = digitalPinToGPIONumber(rxPin); + txPin = digitalPinToGPIONumber(txPin); + if(_uart) { // in this case it is a begin() over a previous begin() - maybe to change baud rate // thus do not disable debug output @@ -500,6 +505,12 @@ void HardwareSerial::setRxInvert(bool invert) // can be called after or before begin() bool HardwareSerial::setPins(int8_t rxPin, int8_t txPin, int8_t ctsPin, int8_t rtsPin) { + // map logical pins to GPIO numbers + rxPin = digitalPinToGPIONumber(rxPin); + txPin = digitalPinToGPIONumber(txPin); + ctsPin = digitalPinToGPIONumber(ctsPin); + rtsPin = digitalPinToGPIONumber(rtsPin); + // uartSetPins() checks if pins are valid and, if necessary, detaches the previous ones return uartSetPins(_uart_nr, rxPin, txPin, ctsPin, rtsPin); } diff --git a/cores/esp32/USB.cpp b/cores/esp32/USB.cpp index 247f6887aa9..ad1df4c22e8 100644 --- a/cores/esp32/USB.cpp +++ b/cores/esp32/USB.cpp @@ -51,7 +51,11 @@ #define USB_WEBUSB_URL "https://espressif.github.io/arduino-esp32/webusb.html" #endif -#if CFG_TUD_DFU_RUNTIME +#if CFG_TUD_DFU +__attribute__((weak)) uint16_t load_dfu_ota_descriptor(uint8_t * dst, uint8_t * itf) { + return 0; +} +#elif CFG_TUD_DFU_RUNTIME static uint16_t load_dfu_descriptor(uint8_t * dst, uint8_t * itf) { #define DFU_ATTRS (DFU_ATTR_CAN_DOWNLOAD | DFU_ATTR_CAN_UPLOAD | DFU_ATTR_MANIFESTATION_TOLERANT) @@ -65,6 +69,9 @@ static uint16_t load_dfu_descriptor(uint8_t * dst, uint8_t * itf) memcpy(dst, descriptor, TUD_DFU_RT_DESC_LEN); return TUD_DFU_RT_DESC_LEN; } +#endif /* CFG_TUD_DFU_RUNTIME */ + +#if CFG_TUD_DFU_RUNTIME // Invoked on DFU_DETACH request to reboot to the bootloader void tud_dfu_runtime_reboot_to_dfu_cb(void) { @@ -207,7 +214,9 @@ ESPUSB::operator bool() const } bool ESPUSB::enableDFU(){ -#if CFG_TUD_DFU_RUNTIME +#if CFG_TUD_DFU + return tinyusb_enable_interface(USB_INTERFACE_DFU, TUD_DFU_DESC_LEN(1), load_dfu_ota_descriptor) == ESP_OK; +#elif CFG_TUD_DFU_RUNTIME return tinyusb_enable_interface(USB_INTERFACE_DFU, TUD_DFU_RT_DESC_LEN, load_dfu_descriptor) == ESP_OK; #endif /* CFG_TUD_DFU_RUNTIME */ return false; diff --git a/cores/esp32/chip-debug-report.cpp b/cores/esp32/chip-debug-report.cpp index 8bcda850d77..aeb0e907dfb 100644 --- a/cores/esp32/chip-debug-report.cpp +++ b/cores/esp32/chip-debug-report.cpp @@ -242,7 +242,11 @@ static void printBoardInfo(void){ static void printPerimanInfo(void){ chip_report_printf("GPIO Info:\n"); chip_report_printf("------------------------------------------\n"); +#if defined(BOARD_HAS_PIN_REMAP) + chip_report_printf(" DPIN|GPIO : BUS_TYPE[bus/unit][chan]\n"); +#else chip_report_printf(" GPIO : BUS_TYPE[bus/unit][chan]\n"); +#endif chip_report_printf(" -------------------------------------- \n"); for(uint8_t i = 0; i < SOC_GPIO_PIN_COUNT; i++){ if(!perimanPinIsValid(i)){ @@ -252,8 +256,17 @@ static void printPerimanInfo(void){ if(type == ESP32_BUS_TYPE_INIT){ continue;//unused pin } - const char* extra_type = perimanGetPinBusExtraType(i); +#if defined(BOARD_HAS_PIN_REMAP) + int dpin = gpioNumberToDigitalPin(i); + if (dpin < 0) { + continue;//pin is not exported + } else { + chip_report_printf(" D%-3d|%4u : ", dpin, i); + } +#else chip_report_printf(" %4u : ", i); +#endif + const char* extra_type = perimanGetPinBusExtraType(i); if(extra_type){ chip_report_printf("%s", extra_type); } diff --git a/cores/esp32/esp32-hal-periman.h b/cores/esp32/esp32-hal-periman.h index 2d91b696f7f..42833b4bab1 100644 --- a/cores/esp32/esp32-hal-periman.h +++ b/cores/esp32/esp32-hal-periman.h @@ -4,6 +4,8 @@ * SPDX-License-Identifier: Apache-2.0 */ +#pragma once + #ifdef __cplusplus extern "C" { diff --git a/cores/esp32/esp32-hal.h b/cores/esp32/esp32-hal.h index 2f53bb2ff66..c2e10dd172a 100644 --- a/cores/esp32/esp32-hal.h +++ b/cores/esp32/esp32-hal.h @@ -86,6 +86,7 @@ void yield(void); #include "esp32-hal-psram.h" #include "esp32-hal-rgb-led.h" #include "esp32-hal-cpu.h" +#include "esp32-hal-periman.h" void analogWrite(uint8_t pin, int value); void analogWriteFrequency(uint8_t pin, uint32_t freq); diff --git a/cores/esp32/io_pin_remap.h b/cores/esp32/io_pin_remap.h new file mode 100644 index 00000000000..92e98604445 --- /dev/null +++ b/cores/esp32/io_pin_remap.h @@ -0,0 +1,142 @@ +#ifndef __IO_PIN_REMAP_H__ +#define __IO_PIN_REMAP_H__ + +#include "Arduino.h" + +#if defined(BOARD_HAS_PIN_REMAP) && !defined(BOARD_USES_HW_GPIO_NUMBERS) + +// Pin remapping functions +int8_t digitalPinToGPIONumber(int8_t digitalPin); +int8_t gpioNumberToDigitalPin(int8_t gpioNumber); + +// Apply pin remapping to API only when building libraries and user sketch +#ifndef ARDUINO_CORE_BUILD + +// Override APIs requiring pin remapping + +// cores/esp32/Arduino.h +#define pulseInLong(pin, args...) pulseInLong(digitalPinToGPIONumber(pin), args) +#define pulseIn(pin, args...) pulseIn(digitalPinToGPIONumber(pin), args) +#define noTone(_pin) noTone(digitalPinToGPIONumber(_pin)) +#define tone(_pin, args...) tone(digitalPinToGPIONumber(_pin), args) + +// cores/esp32/esp32-hal.h +#define analogGetChannel(pin) analogGetChannel(digitalPinToGPIONumber(pin)) +#define analogWrite(pin, value) analogWrite(digitalPinToGPIONumber(pin), value) +#define analogWriteFrequency(pin, freq) analogWriteFrequency(digitalPinToGPIONumber(pin), freq) +#define analogWriteResolution(pin, bits) analogWriteResolution(digitalPinToGPIONumber(pin), bits) + +// cores/esp32/esp32-hal-adc.h +#define analogRead(pin) analogRead(digitalPinToGPIONumber(pin)) +#define analogReadMilliVolts(pin) analogReadMilliVolts(digitalPinToGPIONumber(pin)) +#define analogSetPinAttenuation(pin, attenuation) analogSetPinAttenuation(digitalPinToGPIONumber(pin), attenuation) + +// cores/esp32/esp32-hal-dac.h +#define dacDisable(pin) dacDisable(digitalPinToGPIONumber(pin)) +#define dacWrite(pin, value) dacWrite(digitalPinToGPIONumber(pin), value) + +// cores/esp32/esp32-hal-gpio.h +#define analogChannelToDigitalPin(channel) gpioNumberToDigitalPin(analogChannelToDigitalPin(channel)) +#define digitalPinToAnalogChannel(pin) digitalPinToAnalogChannel(digitalPinToGPIONumber(pin)) +#define digitalPinToTouchChannel(pin) digitalPinToTouchChannel(digitalPinToGPIONumber(pin)) +#define digitalRead(pin) digitalRead(digitalPinToGPIONumber(pin)) +#define attachInterruptArg(pin, fcn, arg, mode) attachInterruptArg(digitalPinToGPIONumber(pin), fcn, arg, mode) +#define attachInterrupt(pin, fcn, mode) attachInterrupt(digitalPinToGPIONumber(pin), fcn, mode) +#define detachInterrupt(pin) detachInterrupt(digitalPinToGPIONumber(pin)) +#define digitalWrite(pin, val) digitalWrite(digitalPinToGPIONumber(pin), val) +#define pinMode(pin, mode) pinMode(digitalPinToGPIONumber(pin), mode) + +// cores/esp32/esp32-hal-i2c.h +#define i2cInit(i2c_num, sda, scl, clk_speed) i2cInit(i2c_num, digitalPinToGPIONumber(sda), digitalPinToGPIONumber(scl), clk_speed) + +// cores/esp32/esp32-hal-i2c-slave.h +#define i2cSlaveInit(num, sda, scl, slaveID, frequency, rx_len, tx_len) i2cSlaveInit(num, digitalPinToGPIONumber(sda), digitalPinToGPIONumber(scl), slaveID, frequency, rx_len, tx_len) + +// cores/esp32/esp32-hal-ledc.h +#define ledcAttach(pin, freq, resolution) ledcAttach(digitalPinToGPIONumber(pin), freq, resolution) +#define ledcWrite(pin, duty) ledcWrite(digitalPinToGPIONumber(pin), duty) +#define ledcWriteTone(pin, freq) ledcWriteTone(digitalPinToGPIONumber(pin), freq) +#define ledcWriteNote(pin, note, octave) ledcWriteNote(digitalPinToGPIONumber(pin), note, octave) +#define ledcRead(pin) ledcRead(digitalPinToGPIONumber(pin)) +#define ledcReadFreq(pin) ledcReadFreq(digitalPinToGPIONumber(pin)) +#define ledcDetach(pin) ledcDetach(digitalPinToGPIONumber(pin)) +#define ledcChangeFrequency(pin, freq, resolution) ledcChangeFrequency(digitalPinToGPIONumber(pin), freq, resolution) + +#define ledcFade(pin, start_duty, target_duty, max_fade_time_ms) ledcFade(digitalPinToGPIONumber(pin), start_duty, target_duty, max_fade_time_ms) +#define ledcFadeWithInterrupt(pin, start_duty, target_duty, max_fade_time_ms, userFunc) ledcFadeWithInterrupt(digitalPinToGPIONumber(pin), start_duty, target_duty, max_fade_time_ms, userFunc) +#define ledcFadeWithInterruptArg(pin, start_duty, target_duty, max_fade_time_ms, userFunc, arg) ledcFadeWithInterruptArg(digitalPinToGPIONumber(pin), start_duty, target_duty, max_fade_time_ms, userFunc, arg) + +// cores/esp32/esp32-hal-matrix.h +#define pinMatrixInAttach(pin, signal, inverted) pinMatrixInAttach(digitalPinToGPIONumber(pin), signal, inverted) +#define pinMatrixOutAttach(pin, function, invertOut, invertEnable) pinMatrixOutAttach(digitalPinToGPIONumber(pin), function, invertOut, invertEnable) +#define pinMatrixOutDetach(pin, invertOut, invertEnable) pinMatrixOutDetach(digitalPinToGPIONumber(pin), invertOut, invertEnable) + +// cores/esp32/esp32-hal-periman.h +#define perimanSetPinBus(pin, type, bus, bus_num, bus_channel) perimanSetPinBus(digitalPinToGPIONumber(pin), type, bus, bus_num, bus_channel) +#define perimanGetPinBus(pin, type) perimanGetPinBus(digitalPinToGPIONumber(pin), type) +#define perimanGetPinBusType(pin) perimanGetPinBusType(digitalPinToGPIONumber(pin)) +#define perimanGetPinBusNum(pin) perimanGetPinBusNum(digitalPinToGPIONumber(pin)) +#define perimanGetPinBusChannel(pin) perimanGetPinBusChannel(digitalPinToGPIONumber(pin)) +#define perimanPinIsValid(pin) perimanPinIsValid(digitalPinToGPIONumber(pin)) +#define perimanSetPinBusExtraType(pin, extra_type) perimanSetPinBusExtraType(digitalPinToGPIONumber(pin), extra_type) +#define perimanGetPinBusExtraType(pin) perimanGetPinBusExtraType(digitalPinToGPIONumber(pin)) + +// cores/esp32/esp32-hal-rgb-led.h +#define neopixelWrite(pin, red_val, green_val, blue_val) neopixelWrite(digitalPinToGPIONumber(pin), red_val, green_val, blue_val) + +// cores/esp32/esp32-hal-rmt.h +#define rmtInit(pin, channel_direction, memsize, frequency_Hz) rmtInit(digitalPinToGPIONumber(pin), channel_direction, memsize, frequency_Hz) +#define rmtWrite(pin, data, num_rmt_symbols, timeout_ms) rmtWrite(digitalPinToGPIONumber(pin), data, num_rmt_symbols, timeout_ms) +#define rmtWriteAsync(pin, data, num_rmt_symbols) rmtWriteAsync(digitalPinToGPIONumber(pin), data, num_rmt_symbols) +#define rmtWriteLooping(pin, data, num_rmt_symbols) rmtWriteLooping(digitalPinToGPIONumber(pin), data, num_rmt_symbols) +#define rmtTransmitCompleted(pin) rmtTransmitCompleted(digitalPinToGPIONumber(pin)) +#define rmtRead(pin, data, num_rmt_symbols, timeout_ms) rmtRead(digitalPinToGPIONumber(pin), data, num_rmt_symbols, timeout_ms) +#define rmtReadAsync(pin, data, num_rmt_symbols) rmtReadAsync(digitalPinToGPIONumber(pin), data, num_rmt_symbols) +#define rmtReceiveCompleted(pin) rmtReceiveCompleted(digitalPinToGPIONumber(pin)) +#define rmtSetRxMaxThreshold(pin, idle_thres_ticks) rmtSetRxMaxThreshold(digitalPinToGPIONumber(pin), idle_thres_ticks) +#define rmtSetCarrier(pin, carrier_en, carrier_level, frequency_Hz, duty_percent) rmtSetCarrier(digitalPinToGPIONumber(pin), carrier_en, carrier_level, frequency_Hz, duty_percent) +#define rmtSetRxMinThreshold(pin, filter_pulse_ticks) rmtSetRxMinThreshold(digitalPinToGPIONumber(pin), filter_pulse_ticks) +#define rmtDeinit(pin) rmtDeinit(digitalPinToGPIONumber(pin)) + +// cores/esp32/esp32-hal-sigmadelta.h +#define sigmaDeltaAttach(pin, freq) sigmaDeltaAttach(digitalPinToGPIONumber(pin), freq) +#define sigmaDeltaWrite(pin, duty) sigmaDeltaWrite(digitalPinToGPIONumber(pin), duty) +#define sigmaDeltaDetach(pin) sigmaDeltaDetach(digitalPinToGPIONumber(pin)) + +// cores/esp32/esp32-hal-spi.h +#define spiAttachSCK(spi, sck) spiAttachSCK(spi, digitalPinToGPIONumber(sck)) +#define spiAttachMISO(spi, miso) spiAttachMISO(spi, digitalPinToGPIONumber(miso)) +#define spiAttachMOSI(spi, mosi) spiAttachMOSI(spi, digitalPinToGPIONumber(mosi)) +#define spiDetachSCK(spi, sck) spiDetachSCK(spi, digitalPinToGPIONumber(sck)) +#define spiDetachMISO(spi, miso) spiDetachMISO(spi, digitalPinToGPIONumber(miso)) +#define spiDetachMOSI(spi, mosi) spiDetachMOSI(spi, digitalPinToGPIONumber(mosi)) +#define spiAttachSS(spi, cs_num, ss) spiAttachSS(spi, cs_num, digitalPinToGPIONumber(ss)) +#define spiDetachSS(spi, ss) spiDetachSS(spi, digitalPinToGPIONumber(ss)) + +// cores/esp32/esp32-hal-touch.h +#define touchInterruptGetLastStatus(pin) touchInterruptGetLastStatus(digitalPinToGPIONumber(pin)) +#define touchRead(pin) touchRead(digitalPinToGPIONumber(pin)) +#define touchAttachInterruptArg(pin, userFunc, arg, threshold) touchAttachInterruptArg(digitalPinToGPIONumber(pin), userFunc, arg, threshold) +#define touchAttachInterrupt(pin, userFunc, threshold) touchAttachInterrupt(digitalPinToGPIONumber(pin), userFunc, threshold) +#define touchDetachInterrupt(pin) touchDetachInterrupt(digitalPinToGPIONumber(pin)) +#define touchSleepWakeUpEnable(pin, threshold) touchSleepWakeUpEnable(digitalPinToGPIONumber(pin), threshold) + +// cores/esp32/esp32-hal-uart.h +#define uartBegin(uart_nr, baudrate, config, rxPin, txPin, rx_buffer_size, tx_buffer_size, inverted, rxfifo_full_thrhd) \ + uartBegin(uart_nr, baudrate, config, digitalPinToGPIONumber(rxPin), digitalPinToGPIONumber(txPin), rx_buffer_size, tx_buffer_size, inverted, rxfifo_full_thrhd) +#define uartSetPins(uart, rxPin, txPin, ctsPin, rtsPin) \ + uartSetPins(uart, digitalPinToGPIONumber(rxPin), digitalPinToGPIONumber(txPin), digitalPinToGPIONumber(ctsPin), digitalPinToGPIONumber(rtsPin)) +#define uartDetachPins(uart, rxPin, txPin, ctsPin, rtsPin) \ + uartDetachPins(uart, digitalPinToGPIONumber(rxPin), digitalPinToGPIONumber(txPin), digitalPinToGPIONumber(ctsPin), digitalPinToGPIONumber(rtsPin)) + +#endif // ARDUINO_CORE_BUILD + +#else + +// pin remapping disabled: use stubs +#define digitalPinToGPIONumber(digitalPin) (digitalPin) +#define gpioNumberToDigitalPin(gpioNumber) (gpioNumber) + +#endif + +#endif /* __GPIO_PIN_REMAP_H__ */ diff --git a/cores/esp32/main.cpp b/cores/esp32/main.cpp index f5d67bc0470..fd51c4123bd 100644 --- a/cores/esp32/main.cpp +++ b/cores/esp32/main.cpp @@ -47,7 +47,7 @@ void loopTask(void *pvParameters) { #if !defined(NO_GLOBAL_INSTANCES) && !defined(NO_GLOBAL_SERIAL) // sets UART0 (default console) RX/TX pins as already configured in boot or as defined in variants/pins_arduino.h - Serial0.setPins(SOC_RX0, SOC_TX0); + Serial0.setPins(gpioNumberToDigitalPin(SOC_RX0), gpioNumberToDigitalPin(SOC_TX0)); #endif #if ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_DEBUG printBeforeSetupInfo(); diff --git a/libraries/ESP_I2S/src/ESP_I2S.cpp b/libraries/ESP_I2S/src/ESP_I2S.cpp index cc743769d42..eee1e1c8e76 100644 --- a/libraries/ESP_I2S/src/ESP_I2S.cpp +++ b/libraries/ESP_I2S/src/ESP_I2S.cpp @@ -1,3 +1,6 @@ +// Disable the automatic pin remapping of the API calls in this file +#define ARDUINO_CORE_BUILD + #include "ESP_I2S.h" #if SOC_I2S_SUPPORTED @@ -230,11 +233,11 @@ bool I2SClass::i2sDetachBus(void * bus_pointer){ // Set pins for STD and TDM mode void I2SClass::setPins(int8_t bclk, int8_t ws, int8_t dout, int8_t din, int8_t mclk){ - _mclk = mclk; - _bclk = bclk; - _ws = ws; - _dout = dout; - _din = din; + _mclk = digitalPinToGPIONumber(mclk); + _bclk = digitalPinToGPIONumber(bclk); + _ws = digitalPinToGPIONumber(ws); + _dout = digitalPinToGPIONumber(dout); + _din = digitalPinToGPIONumber(din); } void I2SClass::setInverted(bool bclk, bool ws, bool mclk){ @@ -246,10 +249,10 @@ void I2SClass::setInverted(bool bclk, bool ws, bool mclk){ // Set pins for PDM TX mode #if SOC_I2S_SUPPORTS_PDM_TX void I2SClass::setPinsPdmTx(int8_t clk, int8_t dout0, int8_t dout1){ - _tx_clk = clk; - _tx_dout0 = dout0; + _tx_clk = digitalPinToGPIONumber(clk); + _tx_dout0 = digitalPinToGPIONumber(dout0); #if (SOC_I2S_PDM_MAX_TX_LINES > 1) - _tx_dout1 = dout1; + _tx_dout1 = digitalPinToGPIONumber(dout1); #endif } #endif @@ -257,12 +260,12 @@ void I2SClass::setPinsPdmTx(int8_t clk, int8_t dout0, int8_t dout1){ // Set pins for PDM RX mode #if SOC_I2S_SUPPORTS_PDM_RX void I2SClass::setPinsPdmRx(int8_t clk, int8_t din0, int8_t din1, int8_t din2, int8_t din3){ - _rx_clk = clk; - _rx_din0 = din0; + _rx_clk = digitalPinToGPIONumber(clk); + _rx_din0 = digitalPinToGPIONumber(din0); #if (SOC_I2S_PDM_MAX_RX_LINES > 1) - _rx_din1 = din1; - _rx_din2 = din2; - _rx_din3 = din3; + _rx_din1 = digitalPinToGPIONumber(din1); + _rx_din2 = digitalPinToGPIONumber(din2); + _rx_din3 = digitalPinToGPIONumber(din3); #endif } #endif diff --git a/libraries/Ethernet/src/ETH.cpp b/libraries/Ethernet/src/ETH.cpp index f3fc5b02468..40c408ee69a 100644 --- a/libraries/Ethernet/src/ETH.cpp +++ b/libraries/Ethernet/src/ETH.cpp @@ -18,6 +18,9 @@ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ +// Disable the automatic pin remapping of the API calls in this file +#define ARDUINO_CORE_BUILD + #include "ETH.h" #include "esp_system.h" #include "esp_event.h" @@ -98,13 +101,13 @@ bool ETHClass::begin(eth_phy_type_t type, uint8_t phy_addr, int mdc, int mdio, i eth_esp32_emac_config_t mac_config = ETH_ESP32_EMAC_DEFAULT_CONFIG(); mac_config.clock_config.rmii.clock_mode = (clock_mode) ? EMAC_CLK_OUT : EMAC_CLK_EXT_IN; mac_config.clock_config.rmii.clock_gpio = (1 == clock_mode) ? EMAC_APPL_CLK_OUT_GPIO : (2 == clock_mode) ? EMAC_CLK_OUT_GPIO : (3 == clock_mode) ? EMAC_CLK_OUT_180_GPIO : EMAC_CLK_IN_GPIO; - mac_config.smi_mdc_gpio_num = mdc; - mac_config.smi_mdio_gpio_num = mdio; + mac_config.smi_mdc_gpio_num = digitalPinToGPIONumber(mdc); + mac_config.smi_mdio_gpio_num = digitalPinToGPIONumber(mdio); - _pin_mcd = mdc; - _pin_mdio = mdio; + _pin_mcd = digitalPinToGPIONumber(mdc); + _pin_mdio = digitalPinToGPIONumber(mdio); _pin_rmii_clock = mac_config.clock_config.rmii.clock_gpio; - _pin_power = power; + _pin_power = digitalPinToGPIONumber(power); if(!perimanClearPinBus(_pin_rmii_clock)){ return false; } if(!perimanClearPinBus(_pin_mcd)){ return false; } @@ -130,7 +133,7 @@ bool ETHClass::begin(eth_phy_type_t type, uint8_t phy_addr, int mdc, int mdio, i eth_phy_config_t phy_config = ETH_PHY_DEFAULT_CONFIG(); phy_config.phy_addr = phy_addr; - phy_config.reset_gpio_num = power; + phy_config.reset_gpio_num = _pin_power; esp_eth_phy_t *phy = NULL; switch(type){ @@ -381,12 +384,12 @@ bool ETHClass::beginSPI(eth_phy_type_t type, uint8_t phy_addr, int cs, int irq, _spi_freq_mhz = spi_freq_mhz; } _phy_type = type; - _pin_cs = cs; - _pin_irq = irq; - _pin_rst = rst; - _pin_sck = sck; - _pin_miso = miso; - _pin_mosi = mosi; + _pin_cs = digitalPinToGPIONumber(cs); + _pin_irq = digitalPinToGPIONumber(irq); + _pin_rst = digitalPinToGPIONumber(rst); + _pin_sck = digitalPinToGPIONumber(sck); + _pin_miso = digitalPinToGPIONumber(miso); + _pin_mosi = digitalPinToGPIONumber(mosi); #if ETH_SPI_SUPPORTS_CUSTOM if(_spi != NULL){ diff --git a/libraries/SD_MMC/src/SD_MMC.cpp b/libraries/SD_MMC/src/SD_MMC.cpp index 67ac8e6e371..8ab5dec14b2 100644 --- a/libraries/SD_MMC/src/SD_MMC.cpp +++ b/libraries/SD_MMC/src/SD_MMC.cpp @@ -12,7 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +// Disable the automatic pin remapping of the API calls in this file +#define ARDUINO_CORE_BUILD + #include "pins_arduino.h" +#include "io_pin_remap.h" #include "SD_MMC.h" #ifdef SOC_SDMMC_HOST_SUPPORTED #include "vfs_api.h" @@ -72,6 +76,15 @@ bool SDMMCFS::setPins(int clk, int cmd, int d0, int d1, int d2, int d3) log_e("SD_MMC.setPins must be called before SD_MMC.begin"); return false; } + + // map logical pins to GPIO numbers + clk = digitalPinToGPIONumber(clk); + cmd = digitalPinToGPIONumber(cmd); + d0 = digitalPinToGPIONumber(d0); + d1 = digitalPinToGPIONumber(d1); + d2 = digitalPinToGPIONumber(d2); + d3 = digitalPinToGPIONumber(d3); + #ifdef SOC_SDMMC_USE_GPIO_MATRIX // SoC supports SDMMC pin configuration via GPIO matrix. Save the pins for later use in SDMMCFS::begin. _pin_clk = (int8_t) clk; diff --git a/libraries/SPI/src/SPI.cpp b/libraries/SPI/src/SPI.cpp index 64607184e2c..251cc48c4fe 100644 --- a/libraries/SPI/src/SPI.cpp +++ b/libraries/SPI/src/SPI.cpp @@ -22,6 +22,7 @@ #include "SPI.h" #if SOC_GPSPI_SUPPORTED +#include "io_pin_remap.h" #include "esp32-hal-log.h" #if !CONFIG_DISABLE_HAL_LOCKS diff --git a/package/package_esp32_index.template.json b/package/package_esp32_index.template.json index 7d9b0e60fed..9c6324af2c4 100644 --- a/package/package_esp32_index.template.json +++ b/package/package_esp32_index.template.json @@ -33,6 +33,9 @@ }, { "name": "ESP32-C3 Dev Board" + }, + { + "name": "Arduino Nano ESP32" } ], "toolsDependencies": [ @@ -90,6 +93,11 @@ "packager": "esp32", "name": "mklittlefs", "version": "3.0.0-gnu12-dc7f933" + }, + { + "packager": "arduino", + "name": "dfu-util", + "version": "0.11.0-arduino5" } ] } diff --git a/platform.txt b/platform.txt index b712f49b437..3286cb93783 100644 --- a/platform.txt +++ b/platform.txt @@ -115,6 +115,9 @@ build.openocdscript.esp32c6=esp32c6-builtin.cfg build.openocdscript.esp32c6=esp32h2-builtin.cfg build.openocdscript={build.openocdscript.{build.mcu}} +# Debug plugin configuration +build.debugconfig={build.mcu}.json + # Custom build options build.opt.name=build_opt.h build.opt.path={build.path}/{build.opt.name} @@ -136,31 +139,41 @@ recipe.hooks.prebuild.4.pattern.windows=cmd /c IF EXIST "{build.source.path}\boo # Check if custom build options exist in the sketch folder recipe.hooks.prebuild.5.pattern=bash -c "[ ! -f "{build.source.path}"/build_opt.h ] || cp -f "{build.source.path}"/build_opt.h "{build.path}"/build_opt.h" -recipe.hooks.prebuild.6.pattern=bash -c "[ -f "{build.path}"/build_opt.h ] || touch "{build.path}"/build_opt.h" +recipe.hooks.prebuild.6.pattern=bash -c "[ -f "{build.path}"/build_opt.h ] || : > "{build.path}"/build_opt.h" recipe.hooks.prebuild.5.pattern.windows=cmd /c if exist "{build.source.path}\build_opt.h" COPY /y "{build.source.path}\build_opt.h" "{build.path}\build_opt.h" recipe.hooks.prebuild.6.pattern.windows=cmd /c if not exist "{build.path}\build_opt.h" type nul > "{build.path}\build_opt.h" +# Set -DARDUINO_CORE_BUILD only on core file compilation +file_opts.path={build.path}/file_opts +recipe.hooks.prebuild.set_core_build_flag.pattern=bash -c ": > '{file_opts.path}'" +recipe.hooks.core.prebuild.set_core_build_flag.pattern=bash -c "echo '-DARDUINO_CORE_BUILD' > '{file_opts.path}'" +recipe.hooks.core.postbuild.set_core_build_flag.pattern=bash -c ": > '{file_opts.path}'" + +recipe.hooks.prebuild.set_core_build_flag.pattern.windows=cmd /c type nul > "{file_opts.path}" +recipe.hooks.core.prebuild.set_core_build_flag.pattern.windows=cmd /c echo "-DARDUINO_CORE_BUILD" > "{file_opts.path}" +recipe.hooks.core.postbuild.set_core_build_flag.pattern.windows=cmd /c type nul > "{file_opts.path}" + # Generate debug.cfg (must be postbuild) recipe.hooks.postbuild.1.pattern=bash -c "[ {build.copy_jtag_files} -eq 0 ] || cp -f "{debug.server.openocd.scripts_dir}"board/{build.openocdscript} "{build.source.path}"/debug.cfg" recipe.hooks.postbuild.1.pattern.windows=cmd /c IF {build.copy_jtag_files}==1 COPY /y "{debug.server.openocd.scripts_dir}board\{build.openocdscript}" "{build.source.path}\debug.cfg" # Generate debug_custom.json -recipe.hooks.postbuild.2.pattern=bash -c "[ {build.copy_jtag_files} -eq 0 ] || cp -f "{runtime.platform.path}"/tools/ide-debug/{build.mcu}.json "{build.source.path}"/debug_custom.json" -recipe.hooks.postbuild.2.pattern.windows=cmd /c IF {build.copy_jtag_files}==1 COPY /y "{runtime.platform.path}\tools\ide-debug\{build.mcu}.json" "{build.source.path}\debug_custom.json" +recipe.hooks.postbuild.2.pattern=bash -c "[ {build.copy_jtag_files} -eq 0 ] || cp -f "{runtime.platform.path}"/tools/ide-debug/{build.debugconfig} "{build.source.path}"/debug_custom.json" +recipe.hooks.postbuild.2.pattern.windows=cmd /c IF {build.copy_jtag_files}==1 COPY /y "{runtime.platform.path}\tools\ide-debug\{build.debugconfig}" "{build.source.path}\debug_custom.json" # Generate chip.svd recipe.hooks.postbuild.3.pattern=bash -c "[ {build.copy_jtag_files} -eq 0 ] || cp -f "{runtime.platform.path}"/tools/ide-debug/svd/{build.mcu}.svd "{build.source.path}"/debug.svd" recipe.hooks.postbuild.3.pattern.windows=cmd /c IF {build.copy_jtag_files}==1 COPY /y "{runtime.platform.path}\tools\ide-debug\svd\{build.mcu}.svd" "{build.source.path}\debug.svd" ## Compile c files -recipe.c.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.c.extra_flags} {compiler.c.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "{source_file}" -o "{object_file}" +recipe.c.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.c.extra_flags} {compiler.c.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "@{file_opts.path}" "{source_file}" -o "{object_file}" ## Compile c++ files -recipe.cpp.o.pattern="{compiler.path}{compiler.cpp.cmd}" {compiler.cpp.extra_flags} {compiler.cpp.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "{source_file}" -o "{object_file}" +recipe.cpp.o.pattern="{compiler.path}{compiler.cpp.cmd}" {compiler.cpp.extra_flags} {compiler.cpp.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "@{file_opts.path}" "{source_file}" -o "{object_file}" ## Compile S files -recipe.S.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.S.extra_flags} {compiler.S.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "{source_file}" -o "{object_file}" +recipe.S.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.S.extra_flags} {compiler.S.flags} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} -DARDUINO_BOARD="{build.board}" -DARDUINO_VARIANT="{build.variant}" -DARDUINO_PARTITION_{build.partitions} {build.extra_flags} {compiler.cpreprocessor.flags} {includes} "@{build.opt.path}" "@{file_opts.path}" "{source_file}" -o "{object_file}" ## Create archives recipe.ar.pattern="{compiler.path}{compiler.ar.cmd}" {compiler.ar.flags} {compiler.ar.extra_flags} "{archive_file_path}" "{object_file}" @@ -211,7 +224,7 @@ pluggable_monitor.required.serial=builtin:serial-monitor debug.executable={build.path}/{build.project_name}.elf debug.toolchain=gcc debug.toolchain.path={tools.{build.tarch}-esp-elf-gdb.path}/bin/ -debug.toolchain.prefix={build.tarch}-{build.target}-elf +debug.toolchain.prefix={build.tarch}-{build.target}-elf- debug.server=openocd debug.server.openocd.script=debug.cfg @@ -264,3 +277,11 @@ tools.esp_ota.upload.protocol=network tools.esp_ota.upload.field.password=Password tools.esp_ota.upload.field.password.secret=true tools.esp_ota.upload.pattern={cmd} -i {upload.port.address} -p {upload.port.properties.port} --auth={upload.field.password} -f "{build.path}/{build.project_name}.bin" + +## Upload Sketch Through DFU OTA +## ------------------------------------------- +tools.dfu-util.path={runtime.tools.dfu-util-0.11.0-arduino5.path} +tools.dfu-util.cmd=dfu-util +tools.dfu-util.upload.params.verbose=-d +tools.dfu-util.upload.params.quiet= +tools.dfu-util.upload.pattern="{path}/{cmd}" --device {vid.0}:{pid.0} -D "{build.path}/{build.project_name}.bin" -Q diff --git a/tools/ide-debug/esp32s3-arduino.json b/tools/ide-debug/esp32s3-arduino.json new file mode 100644 index 00000000000..559d2878cbe --- /dev/null +++ b/tools/ide-debug/esp32s3-arduino.json @@ -0,0 +1,18 @@ +{ + "name":"Arduino on ESP32-S3", + "toolchainPrefix":"xtensa-esp32s3-elf", + "svdFile":"debug.svd", + "request":"attach", + "overrideAttachCommands":[ + "set remote hardware-watchpoint-limit 2", + "monitor reset halt", + "monitor gdb_sync", + "thb setup", + "interrupt" + ], + "overrideRestartCommands":[ + "monitor reset halt", + "monitor gdb_sync", + "interrupt" + ] +} diff --git a/tools/partitions/app3M_fat9M_fact512k_16MB.csv b/tools/partitions/app3M_fat9M_fact512k_16MB.csv new file mode 100644 index 00000000000..dac4603e01a --- /dev/null +++ b/tools/partitions/app3M_fat9M_fact512k_16MB.csv @@ -0,0 +1,9 @@ +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x5000, +otadata, data, ota, 0xe000, 0x2000, +app0, app, ota_0, 0x10000, 0x300000, +app1, app, ota_1, 0x310000, 0x300000, +ffat, data, fat, 0x610000, 0x960000, +factory, app, factory, 0xF70000, 0x80000, +coredump, data, coredump, 0xFF0000, 0x10000, +# to create/use ffat, see https://github.com/marcmerlin/esp32_fatfsimage diff --git a/tools/partitions/app3M_spiffs9M_fact512k_16MB.csv b/tools/partitions/app3M_spiffs9M_fact512k_16MB.csv new file mode 100644 index 00000000000..3b8909da325 --- /dev/null +++ b/tools/partitions/app3M_spiffs9M_fact512k_16MB.csv @@ -0,0 +1,8 @@ +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x5000, +otadata, data, ota, 0xe000, 0x2000, +app0, app, ota_0, 0x10000, 0x300000, +app1, app, ota_1, 0x310000, 0x300000, +spiffs, data, spiffs, 0x610000, 0x960000, +factory, app, factory, 0xF70000, 0x80000, +coredump, data, coredump, 0xFF0000, 0x10000, diff --git a/variants/arduino_nano_nora/dfu_callbacks.cpp b/variants/arduino_nano_nora/dfu_callbacks.cpp new file mode 100644 index 00000000000..3695db80ba6 --- /dev/null +++ b/variants/arduino_nano_nora/dfu_callbacks.cpp @@ -0,0 +1,116 @@ +#include "Arduino.h" + +#include +#include + +// defines an "Update" object accessed only by this translation unit +// (also, the object requires MD5Builder internally) +namespace { +// ignore '{anonymous}::MD5Builder::...() defined but not used' warnings +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +#include "../../libraries/Update/src/Updater.cpp" +#include "../../cores/esp32/MD5Builder.cpp" +#pragma GCC diagnostic pop +} + +#define ALT_COUNT 1 + +//--------------------------------------------------------------------+ +// DFU callbacks +// Note: alt is used as the partition number, in order to support multiple partitions like FLASH, EEPROM, etc. +//--------------------------------------------------------------------+ + +uint16_t load_dfu_ota_descriptor(uint8_t * dst, uint8_t * itf) +{ +#define DFU_ATTRS (DFU_ATTR_CAN_DOWNLOAD | DFU_ATTR_CAN_UPLOAD | DFU_ATTR_MANIFESTATION_TOLERANT) + + uint8_t str_index = tinyusb_add_string_descriptor("Arduino DFU"); + uint8_t descriptor[TUD_DFU_DESC_LEN(ALT_COUNT)] = { + // Interface number, string index, attributes, detach timeout, transfer size */ + TUD_DFU_DESCRIPTOR(*itf, ALT_COUNT, str_index, DFU_ATTRS, 100, CFG_TUD_DFU_XFER_BUFSIZE), + }; + *itf+=1; + memcpy(dst, descriptor, TUD_DFU_DESC_LEN(ALT_COUNT)); + return TUD_DFU_DESC_LEN(ALT_COUNT); +} + +// Invoked right before tud_dfu_download_cb() (state=DFU_DNBUSY) or tud_dfu_manifest_cb() (state=DFU_MANIFEST) +// Application return timeout in milliseconds (bwPollTimeout) for the next download/manifest operation. +// During this period, USB host won't try to communicate with us. +uint32_t tud_dfu_get_timeout_cb(uint8_t alt, uint8_t state) +{ + if ( state == DFU_DNBUSY ) + { + // longest delay for Flash writing + return 10; + } + else if (state == DFU_MANIFEST) + { + // time for esp32_ota_set_boot_partition to check final image + return 100; + } + + return 0; +} + +// Invoked when received DFU_DNLOAD (wLength>0) following by DFU_GETSTATUS (state=DFU_DNBUSY) requests +// This callback could be returned before flashing op is complete (async). +// Once finished flashing, application must call tud_dfu_finish_flashing() +void tud_dfu_download_cb(uint8_t alt, uint16_t block_num, uint8_t const* data, uint16_t length) +{ + if (!Update.isRunning()) + { + // this is the first data block, start update if possible + if (!Update.begin()) + { + tud_dfu_finish_flashing(DFU_STATUS_ERR_TARGET); + return; + } + } + + // write a block of data to Flash + // XXX: Update API is needlessly non-const + size_t written = Update.write(const_cast(data), length); + tud_dfu_finish_flashing((written == length) ? DFU_STATUS_OK : DFU_STATUS_ERR_WRITE); +} + +// Invoked when download process is complete, received DFU_DNLOAD (wLength=0) following by DFU_GETSTATUS (state=Manifest) +// Application can do checksum, or actual flashing if buffered entire image previously. +// Once finished flashing, application must call tud_dfu_finish_flashing() +void tud_dfu_manifest_cb(uint8_t alt) +{ + (void) alt; + bool ok = Update.end(true); + + // flashing op for manifest is complete + tud_dfu_finish_flashing(ok? DFU_STATUS_OK : DFU_STATUS_ERR_VERIFY); +} + +// Invoked when received DFU_UPLOAD request +// Application must populate data with up to length bytes and +// Return the number of written bytes +uint16_t tud_dfu_upload_cb(uint8_t alt, uint16_t block_num, uint8_t* data, uint16_t length) +{ + (void) alt; + (void) block_num; + (void) data; + (void) length; + + // not implemented + return 0; +} + +// Invoked when the Host has terminated a download or upload transfer +void tud_dfu_abort_cb(uint8_t alt) +{ + (void) alt; + // ignore +} + +// Invoked when a DFU_DETACH request is received +void tud_dfu_detach_cb(void) +{ + // done, reboot + esp_restart(); +} diff --git a/variants/arduino_nano_nora/double_tap.c b/variants/arduino_nano_nora/double_tap.c new file mode 100644 index 00000000000..b98d5dded64 --- /dev/null +++ b/variants/arduino_nano_nora/double_tap.c @@ -0,0 +1,68 @@ +#include + +#include +#include +#include + +#include "double_tap.h" + +#define NUM_TOKENS 3 +static const uint32_t MAGIC_TOKENS[NUM_TOKENS] = { + 0xf01681de, 0xbd729b29, 0xd359be7a, +}; + +static void *magic_area; +static uint32_t backup_area[NUM_TOKENS]; + +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) +// Current IDF does not map external RAM to a fixed address. +// The actual VMA depends on other enabled devices, so the precise +// location must be discovered. +#include +#include +static uintptr_t get_extram_data_high(void) { + // get a pointer into SRAM area (only the address is useful) + void *psram_ptr = heap_caps_malloc(16, MALLOC_CAP_SPIRAM); + heap_caps_free(psram_ptr); + + // keep moving backwards until leaving PSRAM area + uintptr_t psram_base_addr = (uintptr_t) psram_ptr; + psram_base_addr &= ~(CONFIG_MMU_PAGE_SIZE - 1); // align to start of page + while (esp_psram_check_ptr_addr((void *) psram_base_addr)) { + psram_base_addr -= CONFIG_MMU_PAGE_SIZE; + } + + // offset is one page from start of PSRAM + return psram_base_addr + CONFIG_MMU_PAGE_SIZE + esp_psram_get_size(); +} +#else +#include +#define get_extram_data_high() ((uintptr_t) SOC_EXTRAM_DATA_HIGH) +#endif + + +void double_tap_init(void) { + // magic location block ends 0x20 bytes from end of PSRAM + magic_area = (void *) (get_extram_data_high() - 0x20 - sizeof(MAGIC_TOKENS)); +} + +void double_tap_mark() { + memcpy(backup_area, magic_area, sizeof(MAGIC_TOKENS)); + memcpy(magic_area, MAGIC_TOKENS, sizeof(MAGIC_TOKENS)); + Cache_WriteBack_Addr((uintptr_t) magic_area, sizeof(MAGIC_TOKENS)); +} + +void double_tap_invalidate() { + if (memcmp(backup_area, MAGIC_TOKENS, sizeof(MAGIC_TOKENS))) { + // different contents: restore backup + memcpy(magic_area, backup_area, sizeof(MAGIC_TOKENS)); + } else { + // clear memory + memset(magic_area, 0, sizeof(MAGIC_TOKENS)); + } + Cache_WriteBack_Addr((uintptr_t) magic_area, sizeof(MAGIC_TOKENS)); +} + +bool double_tap_check_match() { + return (memcmp(magic_area, MAGIC_TOKENS, sizeof(MAGIC_TOKENS)) == 0); +} diff --git a/variants/arduino_nano_nora/double_tap.h b/variants/arduino_nano_nora/double_tap.h new file mode 100644 index 00000000000..e797f4f64fd --- /dev/null +++ b/variants/arduino_nano_nora/double_tap.h @@ -0,0 +1,20 @@ +#ifndef __DOUBLE_TAP_H__ +#define __DOUBLE_TAP_H__ + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +void double_tap_init(void); +void double_tap_mark(void); +void double_tap_invalidate(void); +bool double_tap_check_match(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __DOUBLE_TAP_H__ */ diff --git a/variants/arduino_nano_nora/extra/nora_recovery/README.md b/variants/arduino_nano_nora/extra/nora_recovery/README.md new file mode 100644 index 00000000000..786027dc6e3 --- /dev/null +++ b/variants/arduino_nano_nora/extra/nora_recovery/README.md @@ -0,0 +1,49 @@ + +# Arduino Nano Nora Recovery Sketch + +This sketch implements the DFU recovery mode logic, called by all sketches +when a double tap on the RESET button is detected. It should not be uploaded +as any other sketch; instead, this should be compiled and then flashed in +the module's `factory` partition. + +## Compilation + +The binary can be compiled with the Arduino 2.x IDE or CLI using the +`nano_nora` variant. In particular, using the CLI the resulting binary +can be exported to the `build` directory with the `-e` switch to +`arduino-cli compile`. + +## Automatic installation + +By replacing the binary in the current folder, automatic installation +can be performed by running the "Upload with Programmer" action on any +sketch in the Arduino 2.x IDE or CLI. In particular, using the CLI the +binary can be installed via the command: + +``` +arduino-cli compile -u --programmer esptool +``` + +## Manual installation + +Once compiled, the binary can also be installed on a board using `esptool.py` +with the following command: + +``` +esptool.py --chip esp32s3 --port "/dev/ttyACM0" --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size 16MB 0xF70000 "nora_recovery.ino.bin" +``` + +where: +- `esptool.py` is located in your core's install path under `tools/esptool_py`; +- `/dev/ttyACM0` is the serial port exposed by the board to be used; +- `0xF70000` is the factory partition address (make sure it matches the + offset in the variant's `{build.partitions}` file); +- `nora_recovery.ino.bin` is the compiled sketch image. + +Due to a BSP issue, the first call to `esptool.py` will enter the hardware +bootloader for programming, but fail with an "Input/output error". This is +a known issue; calling the program again with the same arguments will now +work correctly. + +Once flashing is complete, a power cycle (or RESET button tap) is required +to leave the `esptool.py` flashing mode and load user sketches. diff --git a/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino b/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino new file mode 100644 index 00000000000..e8ec998d9ab --- /dev/null +++ b/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino @@ -0,0 +1,99 @@ +#include "USB.h" + +#define USB_TIMEOUT_MS 15000 +#define POLL_DELAY_MS 60 +#define FADESTEP 8 + +void pulse_led() { + static uint32_t pulse_width = 0; + static uint8_t dir = 0; + + if (dir) { + pulse_width -= FADESTEP; + if (pulse_width < FADESTEP) { + dir = 0U; + pulse_width = FADESTEP; + } + } else { + pulse_width += FADESTEP; + if (pulse_width > 255) { + dir = 1U; + pulse_width = 255; + } + } + + analogWrite(LED_GREEN, pulse_width); +} + +#include +#include +#include +#include +const esp_partition_t *find_previous_firmware() { + extern bool _recovery_active; + if (!_recovery_active) { + // user flashed this recovery sketch to an OTA partition + // stay here and wait for a proper firmware + return NULL; + } + + // booting from factory partition, look for a valid OTA image + esp_partition_iterator_t it = esp_partition_find(ESP_PARTITION_TYPE_APP, ESP_PARTITION_SUBTYPE_ANY, NULL); + for (; it != NULL; it = esp_partition_next(it)) { + const esp_partition_t *part = esp_partition_get(it); + if (part->subtype != ESP_PARTITION_SUBTYPE_APP_FACTORY) { + esp_partition_pos_t candidate = { part->address, part->size }; + esp_image_metadata_t meta; + if (esp_image_verify(ESP_IMAGE_VERIFY_SILENT, &candidate, &meta) == ESP_OK) { + // found, use it + return part; + } + } + } + + return NULL; +} + +const esp_partition_t *user_part = NULL; + +void setup() { + user_part = find_previous_firmware(); + if (user_part) + esp_ota_set_boot_partition(user_part); + + extern bool _recovery_marker_found; + if (!_recovery_marker_found && user_part) { + // recovery marker not found, probable cold start + // try starting previous firmware immediately + esp_restart(); + } + + // recovery marker found, or nothing else to load + printf("Recovery firmware started, waiting for USB\r\n"); +} + +void loop() { + static int elapsed_ms = 0; + + pulse_led(); + delay(POLL_DELAY_MS); + if (USB) { + // wait indefinitely for DFU to complete + elapsed_ms = 0; + } else { + // wait for USB connection + elapsed_ms += POLL_DELAY_MS; + } + + if (elapsed_ms > USB_TIMEOUT_MS) { + elapsed_ms = 0; + // timed out, try loading previous firmware + if (user_part) { + // there was a valid FW image, load it + analogWrite(LED_GREEN, 255); + printf("Leaving recovery firmware\r\n"); + delay(200); + esp_restart(); // does not return + } + } +} diff --git a/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino.bin b/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino.bin new file mode 100644 index 00000000000..ee5e7d5452e Binary files /dev/null and b/variants/arduino_nano_nora/extra/nora_recovery/nora_recovery.ino.bin differ diff --git a/variants/arduino_nano_nora/io_pin_remap.cpp b/variants/arduino_nano_nora/io_pin_remap.cpp new file mode 100644 index 00000000000..1ff3a7a45c4 --- /dev/null +++ b/variants/arduino_nano_nora/io_pin_remap.cpp @@ -0,0 +1,72 @@ +#if defined(BOARD_HAS_PIN_REMAP) && !defined(ARDUINO_CORE_BUILD) +// -DARDUINO_CORE_BUILD must be set for core files only, to avoid extra +// remapping steps that would create all sorts of issues in the core. +// Removing -DBOARD_HAS_PIN_REMAP at least does correctly restore the +// use of GPIO numbers in the API. +#error This build system is not supported. Please rebuild without BOARD_HAS_PIN_REMAP. +#endif + +#if !defined(BOARD_HAS_PIN_REMAP) +// This board uses pin mapping but the build system has disabled it +#warning The build system forces the Arduino API to use GPIO numbers on a board that has custom pin mapping. +#elif defined(BOARD_USES_HW_GPIO_NUMBERS) +// The user has chosen to disable pin mappin. +#warning The Arduino API will use GPIO numbers for this build. +#endif + +#include "Arduino.h" + +// NOTE: This must match with the remapped pin sequence in pins_arduino.h +static const int8_t TO_GPIO_NUMBER[] = { + 44, // [ 0] D0, RX + 43, // [ 1] D1, TX + 5, // [ 2] D2 + 6, // [ 3] D3, CTS + 7, // [ 4] D4, DSR + 8, // [ 5] D5 + 9, // [ 6] D6 + 10, // [ 7] D7 + 17, // [ 8] D8 + 18, // [ 9] D9 + 21, // [10] D10, SS + 38, // [11] D11, MOSI + 47, // [12] D12, MISO + 48, // [13] D13, SCK, LED_BUILTIN + 46, // [14] LED_RED + 0, // [15] LED_GREEN + 45, // [16] LED_BLUE, RTS + 1, // [17] A0, DTR + 2, // [18] A1 + 3, // [19] A2 + 4, // [20] A3 + 11, // [21] A4, SDA + 12, // [22] A5, SCL + 13, // [23] A6 + 14, // [24] A7 +}; + +#if defined(BOARD_HAS_PIN_REMAP) && !defined(BOARD_USES_HW_GPIO_NUMBERS) + +int8_t digitalPinToGPIONumber(int8_t digitalPin) +{ + if ((digitalPin < 0) || (digitalPin >= NUM_DIGITAL_PINS)) + return -1; + return TO_GPIO_NUMBER[digitalPin]; +} + +int8_t gpioNumberToDigitalPin(int8_t gpioNumber) +{ + if (gpioNumber < 0) + return -1; + + // slow linear table lookup + for (int8_t digitalPin = 0; digitalPin < NUM_DIGITAL_PINS; ++digitalPin) { + if (TO_GPIO_NUMBER[digitalPin] == gpioNumber) + return digitalPin; + } + + // not found + return -1; +} + +#endif diff --git a/variants/arduino_nano_nora/pins_arduino.h b/variants/arduino_nano_nora/pins_arduino.h new file mode 100644 index 00000000000..ea5d882573c --- /dev/null +++ b/variants/arduino_nano_nora/pins_arduino.h @@ -0,0 +1,108 @@ +#ifndef Pins_Arduino_h +#define Pins_Arduino_h + +#include + +#define USB_VID 0x2341 +#define USB_PID 0x0070 + +#ifndef __cplusplus +#define constexpr const +#endif + +// primary pin names + +#if defined(BOARD_HAS_PIN_REMAP) && !defined(BOARD_USES_HW_GPIO_NUMBERS) + +// Arduino style definitions (API uses Dx) + +static constexpr uint8_t D0 = 0; // also RX +static constexpr uint8_t D1 = 1; // also TX +static constexpr uint8_t D2 = 2; +static constexpr uint8_t D3 = 3; // also CTS +static constexpr uint8_t D4 = 4; // also DSR +static constexpr uint8_t D5 = 5; +static constexpr uint8_t D6 = 6; +static constexpr uint8_t D7 = 7; +static constexpr uint8_t D8 = 8; +static constexpr uint8_t D9 = 9; +static constexpr uint8_t D10 = 10; // also SS +static constexpr uint8_t D11 = 11; // also MOSI +static constexpr uint8_t D12 = 12; // also MISO +static constexpr uint8_t D13 = 13; // also SCK, LED_BUILTIN +static constexpr uint8_t LED_RED = 14; +static constexpr uint8_t LED_GREEN = 15; +static constexpr uint8_t LED_BLUE = 16; // also RTS + +static constexpr uint8_t A0 = 17; // also DTR +static constexpr uint8_t A1 = 18; +static constexpr uint8_t A2 = 19; +static constexpr uint8_t A3 = 20; +static constexpr uint8_t A4 = 21; // also SDA +static constexpr uint8_t A5 = 22; // also SCL +static constexpr uint8_t A6 = 23; +static constexpr uint8_t A7 = 24; + +#else + +// ESP32-style definitions (API uses GPIOx) + +static constexpr uint8_t D0 = 44; // also RX +static constexpr uint8_t D1 = 43; // also TX +static constexpr uint8_t D2 = 5; +static constexpr uint8_t D3 = 6; // also CTS +static constexpr uint8_t D4 = 7; // also DSR +static constexpr uint8_t D5 = 8; +static constexpr uint8_t D6 = 9; +static constexpr uint8_t D7 = 10; +static constexpr uint8_t D8 = 17; +static constexpr uint8_t D9 = 18; +static constexpr uint8_t D10 = 21; // also SS +static constexpr uint8_t D11 = 38; // also MOSI +static constexpr uint8_t D12 = 47; // also MISO +static constexpr uint8_t D13 = 48; // also SCK, LED_BUILTIN +static constexpr uint8_t LED_RED = 46; +static constexpr uint8_t LED_GREEN = 0; +static constexpr uint8_t LED_BLUE = 45; // also RTS + +static constexpr uint8_t A0 = 1; // also DTR +static constexpr uint8_t A1 = 2; +static constexpr uint8_t A2 = 3; +static constexpr uint8_t A3 = 4; +static constexpr uint8_t A4 = 11; // also SDA +static constexpr uint8_t A5 = 12; // also SCL +static constexpr uint8_t A6 = 13; +static constexpr uint8_t A7 = 14; + +#endif + +// alternate pin functions + +static constexpr uint8_t LED_BUILTIN = D13; + +static constexpr uint8_t TX = D1; +static constexpr uint8_t RX = D0; +static constexpr uint8_t RTS = LED_BLUE; +static constexpr uint8_t CTS = D3; +static constexpr uint8_t DTR = A0; +static constexpr uint8_t DSR = D4; + +static constexpr uint8_t SS = D10; +static constexpr uint8_t MOSI = D11; +static constexpr uint8_t MISO = D12; +static constexpr uint8_t SCK = D13; + +static constexpr uint8_t SDA = A4; +static constexpr uint8_t SCL = A5; + +#define PIN_I2S_SCK D7 +#define PIN_I2S_FS D8 +#define PIN_I2S_SD D9 +#define PIN_I2S_SD_OUT D9 // same as bidir +#define PIN_I2S_SD_IN D10 + +#ifndef __cplusplus +#undef constexpr +#endif + +#endif /* Pins_Arduino_h */ diff --git a/variants/arduino_nano_nora/variant.cpp b/variants/arduino_nano_nora/variant.cpp new file mode 100644 index 00000000000..cfdd503d949 --- /dev/null +++ b/variants/arduino_nano_nora/variant.cpp @@ -0,0 +1,104 @@ +// Enable pin remapping in this file, so pin constants are meaningful +#undef ARDUINO_CORE_BUILD + +#include "Arduino.h" + +#include "double_tap.h" + +#include +#include +#include + +extern "C" { + void initVariant() { + // nothing to do + } +} + +// global, accessible from recovery sketch +bool _recovery_marker_found; // double tap detected +bool _recovery_active; // running from factory partition + +#define DELAY_US 10000 +#define FADESTEP 8 +static void rgb_pulse_delay(void) +{ + // Bv R^ G x + int widths[4] = { 192, 64, 0, 0 }; + int dec_led = 0; + + // initialize RGB signals from weak pinstraps + pinMode(LED_RED, OUTPUT); + pinMode(LED_GREEN, OUTPUT); + pinMode(LED_BLUE, OUTPUT); + while (dec_led < 3) { + widths[dec_led] -= FADESTEP; + widths[dec_led+1] += FADESTEP; + if (widths[dec_led] <= 0) { + widths[dec_led] = 0; + dec_led = dec_led+1; + widths[dec_led] = 255; + } + + analogWrite(LED_RED, 255-widths[1]); + analogWrite(LED_GREEN, 255-widths[2]); + analogWrite(LED_BLUE, 255-widths[0]); + delayMicroseconds(DELAY_US); + } + + // reset pins to digital HIGH before leaving + digitalWrite(LED_RED, HIGH); + digitalWrite(LED_GREEN, HIGH); + digitalWrite(LED_BLUE, HIGH); +} + +static void NANO_ESP32_enter_bootloader(void) +{ + if (!_recovery_active) { + // check for valid partition scheme + const esp_partition_t *ota_part = esp_ota_get_next_update_partition(NULL); + const esp_partition_t *fact_part = esp_partition_find_first(ESP_PARTITION_TYPE_APP, ESP_PARTITION_SUBTYPE_APP_FACTORY, NULL); + if (ota_part && fact_part) { + // set tokens so the recovery FW will find them + double_tap_mark(); + // invalidate other OTA image + esp_partition_erase_range(ota_part, 0, 4096); + // activate factory partition + esp_ota_set_boot_partition(fact_part); + } + } + + esp_restart(); +} + +static void boot_double_tap_logic() +{ + const esp_partition_t *part = esp_ota_get_running_partition(); + _recovery_active = (part->subtype == ESP_PARTITION_SUBTYPE_APP_FACTORY); + + double_tap_init(); + + _recovery_marker_found = double_tap_check_match(); + if (_recovery_marker_found && !_recovery_active) { + // double tap detected in user application, reboot to factory + NANO_ESP32_enter_bootloader(); + } + + // delay with mark set then proceed + // - for normal startup, to detect first double tap + // - in recovery mode, to ignore several short presses + double_tap_mark(); + rgb_pulse_delay(); + double_tap_invalidate(); +} + +namespace { + class DoubleTap { + public: + DoubleTap() { + boot_double_tap_logic(); + } + }; + + DoubleTap dt __attribute__ ((init_priority (101))); +}