You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Board: ESP32 Dev Module
Core Installation version: 2.0.0
IDE name: Arduino IDE
Description:
in my Code i'am reading a Servosignal with RMT Module. The RMT ISR is initialized with IDF functions as IRAM ISR.
In the IRAM ISR i'am working with the Timer:
timerWrite(timer, 0);
if (!timerAlarmEnabled(timer)) {
timerAlarmEnable(timer);
This ISR must run in IRAM, because it have to work when writing to internal Flash in Loop.
In Loop() i write some Logs to internal FFAT and write to the EEPROM Emulation.
But with Core Version 2.0.0 i get a Crash or TimerGroupWadtchdog when loop() writes to Flash and ISR is executed.
With Core Version 1.6.0 everything was fine.
My Solution:
i set all my used timer functions to IRAM_ATTR in esp32-hal-timer.c
How is the Solution for Future Releases? Everytime a rewrite of the Core?
Or using IDF Timer functions or directly working on the Timer Registers?
Maybe 2 functions? For Example timerWrite() and IRAMtimerWrite() for saving IRAM space when not used/wanted
Sketch:
// the related ISR and init'svoid IRAM_ATTR rmt_isr_handler(void* arg) {
uint32_t intr_st = RMT.int_st.val; // get RMT Status -> Interrupt source (kann nur RMT CH1 receive sein)
RMT.int_clr.val = intr_st; // Clear the Int-Flag which is set
RMT.conf_ch[1].conf1.rx_en = 0; // disable receiver
RMT.conf_ch[1].conf1.mem_owner = RMT_MEM_OWNER_TX; // sonst wird Servo länge nie geändert
servo_tmp = RMTMEM.chan[1].data32[0].duration0; // lese die Input Dauer -> 1 = 1µsif(servo_tmp > throttle){
RMTMEM.chan[2].data32[0].duration0 = throttle; // throttle ist der aktuelle Limit wert
throttle_output = throttle; // der neue Output wert
}
else{
RMTMEM.chan[2].data32[0].duration0 = servo_tmp; // servo_tmp ist der Input wert (kein Limit)
throttle_output = servo_tmp; // der neue Output wert
}
RMT.conf_ch[2].conf1.mem_rd_rst = 1; // resette Output
RMT.conf_ch[2].conf1.mem_rd_rst = 0; // resette Output//RMT.int_clr.ch2_tx_end = 1; // Clear Interrupt Flag -> bereits oben erledigt (sollte auch garnicht aktiv sein)
RMT.conf_ch[2].conf1.tx_start = 1; // Starte Output//rmt_tx_start(rmt_tx_channel.channel, 1); // IDF funktion zum resetten und startenif (servo_tmp != 0) {
timerWrite(timer, 0);
raw_analog_input = true;
if (!timerAlarmEnabled(timer)) {
timerAlarmEnable(timer);
}
}
RMT.conf_ch[1].conf1.mem_wr_rst = 1; // resette Input
RMT.conf_ch[1].conf1.mem_owner = RMT_MEM_OWNER_RX; // sonst wird Servo länge nie geändert
RMT.conf_ch[1].conf1.rx_en = 1; // Enable Input
}
void IRAM_ATTR Failsafe() {
raw_analog_input = false;
throttle = min_analog;
throttle_input = min_analog;
throttle_output = min_analog;
timerAlarmDisable(timer);
}
voidinit_PPM(void) {
rmt_rx_channel.channel = RMT_CHANNEL_1; // RMT Channel 1
rmt_rx_channel.gpio_num = (gpio_num_t) SERVO_IN; // RMT Mapped GPIO
rmt_rx_channel.clk_div = RMT_CLK_DIV; // RMT_Clock auf 1us?
rmt_rx_channel.mem_block_num = 1;
rmt_rx_channel.rmt_mode = RMT_MODE_RX; // RMT Mode RX
rmt_rx_channel.rx_config.filter_en = true; // Filter aktiv
rmt_rx_channel.rx_config.filter_ticks_thresh = 250; // Pulse unter 250 werden ignoriert (0...255)
rmt_rx_channel.rx_config.idle_threshold = RMT_RX_MAX_US; // Pulse über 2500 werden ignoriert -> Gleichzeitig die Verzögerung zw. Puls und ausführung der ISRrmt_config(&rmt_rx_channel);
rmt_set_rx_intr_en(rmt_rx_channel.channel, true);
rmt_rx_start(rmt_rx_channel.channel, 1);
rmt_tx_channel.channel = RMT_CHANNEL_2; // RMT Channel 2
rmt_tx_channel.gpio_num = (gpio_num_t) SERVO_OUT; // RMT Mapped GPIO
rmt_tx_channel.clk_div = RMT_CLK_DIV; // RMT_Clock auf 1us
rmt_tx_channel.mem_block_num = 1;
rmt_tx_channel.rmt_mode = RMT_MODE_TX; // RMT Mode TX
rmt_tx_channel.tx_config.loop_en = 0; // disable loop
rmt_tx_channel.tx_config.carrier_en = 0; // disable carrier
rmt_tx_channel.tx_config.idle_output_en = 0; // activate output while idle//rmt_tx_channel.tx_config.idle_level = RMT_IDLE_LEVEL_LOW; // output level to 0 when idle//rmt_tx_channel.tx_config.carrier_duty_percent = 50; // must be set to prevent errors - not used//rmt_tx_channel.tx_config.carrier_freq_hz = 5000; // must be set to prevent errors - not used//rmt_tx_channel.tx_config.carrier_level = RMT_CARRIER_LEVEL_HIGH; // must be set to prevent errors - not usedrmt_config(&rmt_tx_channel); // set Config//rmt_tx_start(rmt_tx_channel.channel, 1); // Output wird in ISR gestartet//rmt_set_tx_intr_en(rmt_tx_channel.channel, true); // Output Interrupt unnötigrmt_isr_register(rmt_isr_handler, NULL, ESP_INTR_FLAG_IRAM, NULL); // ESP_INTR_FLAG_IRAM
RMTMEM.chan[2].data32[0].duration0 = 0; // Output Idle/Default value
RMTMEM.chan[2].data32[0].level0 = 1; // Output Idle/Default value
RMTMEM.chan[2].data32[0].duration1 = 0; // Output Idle/Default value
RMTMEM.chan[2].data32[0].level1 = 0; // Output Idle/Default value
}
voidinit_Failsafe(void) {
timer = timerBegin(3, 80, true);
timerAttachInterrupt(timer, &Failsafe, false/*true*/);
timerAlarmWrite(timer, 100000, true); // Timer Interrupt 100ms//timerAlarmEnable(timer); // Timer wird enabled wenn Servo Signal erkannt (in RMT ISR)
Serial.println("Init Failsafe");
systime = (millis() / 1000) + startsystime;
}
Debug Messages:
Guru Meditation Error: Core 1 panic'ed (IllegalInstruction). Exception was unhandled.
Memory dump at 0x40144020: 0000f01d 88004136 c0190c02
Core 1 register dump:
PC : 0x40144026 PS : 0x00060031 A0 : 0x40085428 A1 : 0x3ffbf110
A2 : 0x3ff56000 A3 : 0x00000001 A4 : 0x3ffc2df8 A5 : 0x40093bbc
A6 : 0x00000000 A7 : 0x00000001 A8 : 0x80081411 A9 : 0x00020f21
A10 : 0x00008000 A11 : 0x00008000 A12 : 0x00000000 A13 : 0x00000000
A14 : 0x3ffd9114 A15 : 0x3ffd90ec SAR : 0x00000000 EXCCAUSE: 0x00000000
EXCVADDR: 0x00000000 LBEG : 0x4009087c LEND : 0x40090892 LCOUNT : 0xffffffff
Backtrace:0x40144023:0x3ffbf1100x40085425:0x3ffbf130 0x4000bfed:0x3ffd9190 0x400820e9:0x3ffd91a0 0x40082524:0x3ffd91d0 0x40099cea:0x3ffd9200 0x40082601:0x3ffd9220 0x40082d27:0x3ffd9240 0x400ffbd5:0x3ffd92a0 0x40101aea:0x3ffd92c0 0x401022a2:0x3ffd92e0 0x40102911:0x3ffd9300 0x401035b7:0x3ffd9350 0x40100cf0:0x3ffd9370 0x40101263:0x3ffd9400 0x4010140d:0x3ffd9480 0x40101939:0x3ffd94a0 0x40100562:0x3ffd94c0 0x400df826:0x3ffd94e0 0x400d9b2b:0x3ffd9500 0x400d4c35:0x3ffd9520 0x400d9fda:0x3ffd9540 0x400f8d57:0x3ffd9570
ELF file SHA256: 0000000000000000
PC: 0x40144026: timerWrite at C:\Users\eric\AppData\Local\Arduino15\packages\esp32\hardware\esp32\2.0.0\cores\esp32\esp32-hal-timer.c line 136
EXCVADDR: 0x00000000
Decoding stack results
0x400820e9: is_page_mapped_in_cache at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/flash_mmap.c line 497
0x40082524: spi_flash_check_and_flush_cache at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/flash_mmap.c line 516
0x40099cea: memspi_host_flush_cache at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/memspi_host_driver.c line 134
0x40082601: flash_end_flush_cache at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/esp_flash_api.c line 161
0x40082d27: esp_flash_write at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/esp_flash_api.c line 808
0x400ffbd5: esp_partition_write at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/partition.c line 457
0x40101aea: nvs::NVSPartition::write(unsigned int, void const*, unsigned int) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_partition.cpp line 59
0x401022a2: nvs::Page::writeEntry(nvs::Item const&) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_page.hpp line 209
0x40102911: nvs::Page::copyItems(nvs::Page&) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_page.cpp line 499
0x401035b7: nvs::PageManager::requestNewPage() at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_pagemanager.cpp line 183
0x40100cf0: nvs::Storage::writeMultiPageBlob(unsigned char, char const*, void const*, unsigned int, nvs::VerOffset) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_storage.cpp line 240
0x40101263: nvs::Storage::writeItem(unsigned char, nvs::ItemType, char const*, void const*, unsigned int) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_storage.cpp line 316
0x4010140d: nvs::Storage::writeItem(unsigned char, nvs::ItemType, char const*, void const*, unsigned int) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_storage.cpp line 274
0x40101939: nvs::NVSHandleSimple::set_blob(char const*, void const*, unsigned int) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_handle_simple.cpp line 52
0x40100562: nvs_set_blob(nvs_handle_t, char const*, void const*, size_t) at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/nvs_flash/src/nvs_api.cpp line 438
0x400df826: EEPROMClass::commit() at C:\Users\eric\AppData\Local\Arduino15\packages\esp32\hardware\esp32\2.0.0\libraries\EEPROM\src\EEPROM.cpp line 198
0x400d9b2b: write_calibration() at C:\Users\eric\AppData\Local\Temp\arduino_build_297970\sketch\Settings.cpp line 299
0x400d4c35: calibration() at C:\Users\eric\AppData\Local\Temp\arduino_build_297970\sketch\Hardware.cpp line 175
0x400d9fda: setup() at C:\Users\eric\Desktop\MCTRL-Firmware\V0_9_1/V0_9_1.ino line 33
0x400f8d57: loopTask(void*) at C:\Users\eric\AppData\Local\Arduino15\packages\esp32\hardware\esp32\2.0.0\cores\esp32\main.cpp line 38
The text was updated successfully, but these errors were encountered:
Hello @ericlangel , I'm closing this issue as Timer was refactored and this was supposed to be solved by both mentioned PRs above. If you will still face issue on latest version 2.0.3-RC1, please reopen it. Thanks for your contribution.
Hardware:
Board: ESP32 Dev Module
Core Installation version: 2.0.0
IDE name: Arduino IDE
Description:
in my Code i'am reading a Servosignal with RMT Module. The RMT ISR is initialized with IDF functions as IRAM ISR.
In the IRAM ISR i'am working with the Timer:
timerWrite(timer, 0);
if (!timerAlarmEnabled(timer)) {
timerAlarmEnable(timer);
This ISR must run in IRAM, because it have to work when writing to internal Flash in Loop.
In Loop() i write some Logs to internal FFAT and write to the EEPROM Emulation.
But with Core Version 2.0.0 i get a Crash or TimerGroupWadtchdog when loop() writes to Flash and ISR is executed.
With Core Version 1.6.0 everything was fine.
My Solution:
i set all my used timer functions to IRAM_ATTR in esp32-hal-timer.c
How is the Solution for Future Releases? Everytime a rewrite of the Core?
Or using IDF Timer functions or directly working on the Timer Registers?
Maybe 2 functions? For Example timerWrite() and IRAMtimerWrite() for saving IRAM space when not used/wanted
Sketch:
Debug Messages:
The text was updated successfully, but these errors were encountered: