Core panic ->dump of ESP32 when calling function in Interrupt

Hello, I’m using the ESP32TimerInterrupt Library, in combination with the functionality of the Encoder Library on a ESP32 dev Module to read an Encoder Value from a micro metal-gear-motor every 1ms with Timer-Interrupt into a global variable to use in an rpm controller. It compiles fine but the serial monitor shows Core dump without any signs of a restart every time. But with the reading of the Encodervalues in main() everything is fine as well as the Interrupt itself works with pin toggle for example just the combination does’t work. Maybe someone can help with this interrupt issue or should i try to implement the timer-interrupt myself without the timer-Interrupt library?

I tried already to remove noInterrupts(); interrupts() or update() from myEncoder::readAndResetLEFT() but that doesn’t change anything. The Core still gets dumped.

If additional Information is usefull just ask.

Serial Monitor:

CPU Frequency in MHZ:
240
Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x400d0d7c  PS      : 0x00060034  A0      : 0x80081554  A1      : 0x3ffbfea0  
A2      : 0x3ffc19c8  A3      : 0x20000000  A4      : 0x00000400  A5      : 0x00000000  
A6      : 0x3ffc65fc  A7      : 0xffffffff  A8      : 0x800810b4  A9      : 0x00000001  
A10     : 0x3ffc19c8  A11     : 0x00000001  A12     : 0x3ffba2c8  A13     : 0x0000abab  
A14     : 0x3ffc7060  A15     : 0x00000000  SAR     : 0x0000000b  EXCCAUSE: 0x00000007  
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000  
Core 1 was running in ISR context:
EPC1    : 0x40087ae8  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x400d0d7c

ELF file SHA256: 0000000000000000

The project is for abstraction reasons split into multiple files. The structure is as follows → main.cpp includes
Here are the important parts:
main.cpp:

#include <Arduino.h>
#include <WiFi.h>
#include <WiFiClient.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include "Drive.h"
#include <iostream>
#include <sstream>
#include <Adafruit_NeoPixel.h>
#include <ESP32TimerInterrupt.h>
#define TIMER0_INTERVAL_MS 1

volatile int32_t encoderValueleft;
volatile int32_t encoderValueright;
Drive drive;
ESP32Timer ITimer0(0);
void IRAM_ATTR TimerHandler0(void)
{
  encoderValueleft = drive.getEncoderValueLEFT();
  encoderValueright = drive.getEncoderValueRIGHT();
}
void setup(){
  Serial.begin(9600);
  Serial.println("CPU Frequency in MHZ:");
  Serial.println(getCpuFrequencyMhz());

  //Timer setup
  ITimer0.attachInterruptInterval(TIMER0_INTERVAL_MS * 1000, TimerHandler0);

  //Drive setup
  drive.setup();
  drive.move(0);
}

Drive.cpp:

myEncoder roboEncoder(50.0, 66.5, 12, {4, 5}, {35, 34});



int32_t Drive::getEncoderValueLEFT(void)
{
  return (roboEncoder.readAndResetLEFT());
}

int32_t Drive::getEncoderValueRIGHT(void)
{
  return (roboEncoder.readAndResetRIGHT());
}

myEncoder.h:

typedef struct
{
  volatile uint32_t *pin1_register;
  volatile uint32_t *pin2_register;
  uint32_t pin1_bitmask;
  uint32_t pin2_bitmask;
  uint8_t state;
  int32_t position;
} Encoder_internal_state_t;


myEncoder.cpp:

#include "myEncoder.h"

int32_t myEncoder::readAndResetRIGHT(){
  noInterrupts();
  update(&libencoderRight);
  int32_t ret = libencoderLeft.position;
  libencoderLeft.position = 0;
  interrupts();
  return ret;
}

int32_t myEncoder::readAndResetLEFT()
{
  noInterrupts();
  update(&libencoderLeft);
  int32_t ret = libencoderRight.position;
  libencoderRight.position = 0;
  interrupts();
  return ret;
}
//                           _______         _______
//               Pin1 ______|       |_______|       |______ Pin1
// negative <---         _______         _______         __      --> positive
//               Pin2 __|       |_______|       |_______|   Pin2

//	new	new	old	old
//	pin2	pin1	pin2	pin1	Result
//	----	----	----	----	------
//	0	0	0	0	no movement
//	0	0	0	1	+1
//	0	0	1	0	-1
//	0	0	1	1	+2  (assume pin1 edges only)
//	0	1	0	0	-1
//	0	1	0	1	no movement
//	0	1	1	0	-2  (assume pin1 edges only)
//	0	1	1	1	+1
//	1	0	0	0	+1
//	1	0	0	1	-2  (assume pin1 edges only)
//	1	0	1	0	no movement
//	1	0	1	1	-1
//	1	1	0	0	+2  (assume pin1 edges only)
//	1	1	0	1	-1
//	1	1	1	0	+1
//	1	1	1	1	no movement
void update(Encoder_internal_state_t *arg)
{

  uint8_t p1val = (((*(arg->pin1_register)) & (arg->pin1_bitmask)) ? 1 : 0);
  uint8_t p2val = (((*(arg->pin2_register)) & (arg->pin2_bitmask)) ? 1 : 0);
  uint8_t state = arg->state & 3;
  if (p1val)
    state |= 4;
  if (p2val)
    state |= 8;
  arg->state = (state >> 2);
  switch (state)
  {
    case 1: case 7: case 8: case 14:
      arg->position++;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 2: case 4: case 11: case 13:
      arg->position--;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 3: case 12:
      arg->position += 2;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 6: case 9:
      arg->position -= 2;
      //Serial.printf("position = %d\n", arg->position);
      return;
  }
}

The first step is looking where it crashes. Activating the crash decoder has been discussed in multiple topics (ESP32, Arduino, Efuse, External Flash, SHA 256 error - #2 by maxgerhardt).

Add

build_type = debug
monitor_filters = esp32_exception_decoder

to the platformio.ini, upload and monitor again.

OK I get a Backtrace now but how do I decode it? Or is it supposed to be decoded already? Sorry I have never done this Crash Backtrace before.

Output now:

CPU Frequency in MHZ:
240
Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x400d0ed0  PS      : 0x00060034  A0      : 0x80081560  A1      : 0x3ffbfea0
A2      : 0x3ffc19c8  A3      : 0x20000000  A4      : 0x00000400  A5      : 0x00000000
A6      : 0x3ffc65fc  A7      : 0xffffffff  A8      : 0x800810b4  A9      : 0x00000000
A10     : 0x3ffc19c8  A11     : 0x00000000  A12     : 0x3ffba2c8  A13     : 0x0000abab
A14     : 0x3ffc7060  A15     : 0x00000000  SAR     : 0x0000000b  EXCCAUSE: 0x00000007
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000
Core 1 was running in ISR context:
EPC1    : 0x40087b03  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x400d0ed0

ELF file SHA256: 0000000000000000

Backtrace: 0x400d0ed0:0x3ffbfea0 0x4008155d:0x3ffbfec0 0x400878e9:0x3ffbfee0 0x40087b00:0x3ffba1f0 0x40084f53:0x3ffba210 0x4008ad1a:

No this didn’t work properly, after the backtrace text there should be the decoded version on it. Full platformio.ini?

In any case, the problem seems clear to me though:

Your ISR handler is marked with IRAM_ATTR

But the sub-functions you call in it are not. Try to also mark them with IRAM_ATTR. I think the whole chain has to be in IRAM.

Here is my Full platformio.ini:

; PlatformIO Project Configuration File
;
;   Build options: build flags, source filter
;   Upload options: custom upload port, speed and extra flags
;   Library options: dependencies, extra library storages
;   Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html

[env:esp32dev]
platform = espressif32
board = esp32dev
framework = arduino
build_type = debug
monitor_filters = esp32_exception_decoder

;lib_deps = https://github.com/PaulStoffregen/Encoder.git

I’ve tried to put IRAM_ATTR on the whole chain down the line but the Output stays the same:

CPU Frequency in MHZ:
240
Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x4008113f  PS      : 0x00060034  A0      : 0x800811c9  A1      : 0x3ffbfe40
A2      : 0x3ffc1810  A3      : 0x00000000  A4      : 0x00000000  A5      : 0x3ffc6530
A6      : 0x00000003  A7      : 0x00060023  A8      : 0xbad00bad  A9      : 0x3f40186c
A10     : 0x00000000  A11     : 0x3ffb1cb0  A12     : 0x3ffc6610  A13     : 0x00000001
A14     : 0x00000000  A15     : 0x3ffb4abc  SAR     : 0x0000000b  EXCCAUSE: 0x00000007
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000
Core 1 was running in ISR context:
EPC1    : 0x40087bbc  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x4008113f

ELF file SHA256: 0000000000000000

Backtrace: 0x4008113f:0x3ffbfe40 0x400811c6:0x3ffbfe60 0x40081092:0x3ffbfe80 0x400810cc:0x3ffbfea0 0x40081625:0x3ffbfec0 0x�

Without all IRAM_ATTR I get a Backtrace:

CPU Frequency in MHZ:
240
Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x400d1278  PS      : 0x00060034  A0      : 0x40087894  A1      : 0x3ffbfec0
A2      : 0x00000000  A3      : 0x00000001  A4      : 0x000000ff  A5      : 0x4008d3a8
A6      : 0x00000000  A7      : 0x1300045c  A8      : 0x80081508  A9      : 0x3ff5f000
A10     : 0x3ffbdc90  A11     : 0x20000000  A12     : 0x00000400  A13     : 0x00000000
A14     : 0x3ffc65fc  A15     : 0xffffffff  SAR     : 0x00000016  EXCCAUSE: 0x00000007
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000
Core 1 was running in ISR context:
EPC1    : 0x40087aa5  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x400d1278

ELF file SHA256: 0000000000000000

Backtrace: 0x400d1278:0x3ffbfec0 0x40087891:0x3ffbfee0 0x40087aa2:0x3ffba1f0 0x40084efb:0x3ffba210 0x4008acc2:0x3ffba230
  #0  0x400d1278:0x3ffbfec0 in TimerHandler0() at src/main.cpp:233
  #1  0x40087891:0x3ffbfee0 in _xt_lowint1 at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/xtensa_vectors.S:1154
  #2  0x40087aa2:0x3ffba1f0 in spi_flash_op_block_func at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/cache_utils.c:203
  #3  0x40084efb:0x3ffba210 in ipc_task at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/ipc.c:62       
  #4  0x4008acc2:0x3ffba230 in vPortTaskWrapper at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/port.c:355 (discriminator 1)
�

So I guess the Problem is in the Timer-Interrupt Library that somehow cannot build an ESP-IDF task ?
I’ll do the Timer Interrupt myself then.

Hm okay then the backtrace decoder seems to be broken in this particular case :confused:

All resources I’m reading ((SOLVED) Guru Meditation Error: Core 1 panic'ed (Cache disabled but cached memory region accessed) ESP32 VSC Platformio · Issue #3634 · espressif/arduino-esp32 · GitHub, Fatal Errors - ESP32 - — ESP-IDF Programming Guide v4.2 documentation) say the error comes from an interrupt routine not being IRAM or it accessing flash memory (e.g, data marked as const in the code).

I’m also seeing you’re calling into noInterrupts() and interrupts() at readAndResetRIGHT and readAndResetLEFT, which should be defined in the Arduino core, and are possibly not in IRAM. Can you remove the call to those?

Does the error go away when you leave the timer ISR completely empty?

As I tried to explain already the Problem is when calling

encoderValueleft = drive.getEncoderValueLEFT();
encoderValueright = drive.getEncoderValueRIGHT();

In the Interrupt Handler. Without it it works fine and I am able to toggle a pin in the ISR aswell just fine. It is really just this function call doesn’t work in the Interrupt.

If I remove the noInterrupt(), and Interrupt() the problem is exactly the same.

I’m trying to reproduce your problem in a minimal example but it won’t crash.

#include <Arduino.h>
#include <ESP32TimerInterrupt.h>
#define TIMER0_INTERVAL_MS 1

volatile int32_t encoderValueleft;
volatile int32_t encoderValueright;

ESP32Timer ITimer0(0);

void IRAM_ATTR sub_function_1() {
    encoderValueleft += 1; 
}

void IRAM_ATTR sub_function_2() {
    encoderValueright += 1; 
}

void IRAM_ATTR TimerHandler0(void)
{
    sub_function_1();
    sub_function_2();
}

void setup()
{
    Serial.begin(115200);
    Serial.println("CPU Frequency in MHZ:");
    Serial.println(getCpuFrequencyMhz());

    // Timer setup
    ITimer0.attachInterruptInterval(TIMER0_INTERVAL_MS * 1000, TimerHandler0);
}

void loop()
{
    Serial.println("Still alive, left = " + String(encoderValueleft) + " right = " + String(encoderValueright));
    delay(1000);
}

has serial output

CPU Frequency in MHZ:
240
Still alive, left = 0 right = 0
Still alive, left = 1000 right = 1000
Still alive, left = 2000 right = 2000
Still alive, left = 3000 right = 3000

Exactly as I expect.

That is, I can call sub-functions from the ISR just fine when they’re marked with IRAM_ATTR.

Let me try reconstructing your code.

To transfer the project to you woudn’t be much of a problem but the least you need I think is the Encoder class.

in main you need:

#include <Arduino.h>
#include "myEncoder.h"
myEncoder roboEncoder(50.0, 66.5, 12, {4, 5}, {35, 34});
roboEncoder.setup();

myEncoder.h:


#ifndef myEncoder_h__
#define myEncoder_h__


#include <Arduino.h>

#define mvAvg_length 5

struct myEncoder_pins
{

  // myEncoder has EncA and EncB pins
  uint8_t encA;
  uint8_t encB;
};

// All the data needed by interrupts is consolidated into this ugly struct
// to facilitate assembly language optimizing of the speed critical update.
// The assembly code uses auto-incrementing addressing modes, so the struct
// must remain in exactly this order.
typedef struct
{
  volatile uint32_t *pin1_register;
  volatile uint32_t *pin2_register;
  uint32_t pin1_bitmask;
  uint32_t pin2_bitmask;
  uint8_t state;
  int32_t position;
} Encoder_internal_state_t;

struct myEncoder_struct{
  //sensor pin (can be any for the esp32 cause function is handled by abstraction matrix)
  myEncoder_pins enc;
  
  // counts per revolution -> rising and falling edge is measured
  unsigned long cntPerRev;

  // amount of counts since start
   volatile long counter;
  // amount of counts since last tie it was updated
  volatile long lastCounter;

  // radius of the wheel
  double radius;

  // wheel rounds per second (moving average)
  double mvAvgOmega[mvAvg_length];
  // wheel rounds per second
  double omega;

  // tangential linearvel of one wheel
  double vel;

  // total distance travelled
  volatile double distance;

};

//Encoder libenc(myEncoder_pins enc.encA, myEncoder_pins enc.encB);

class myEncoder{

    public:
      /**
       * Configure PWM parameter
       * 
       * @param[in] rate rate on which counts are updated -> higher rate leads to larger errors on small speeds
       * @param[in] wheelDiameter Diameter of wheel in mm
       * @param[in] countsPerRevolution counts per revolution -> rising and falling edge is measured
       * @param[in] enc1pin sensor pin (can be any for the esp32 because function is handled by hardware abstraction matrix)
       * @param[in] enc2pin sensor pin (can be any for the esp32 because function is handled by hardware abstraction matrix)
      */
      myEncoder(double rate, double wheelDiameter, unsigned long countsPerRevolution, myEncoder_pins enc1, myEncoder_pins enc2);
      //Encoder myEnc(myEncoder_pins enc1, myEncoder_pins enc2);
      /**
       * Destructor does not do anything
      */
      ~myEncoder();

      // void IRAM_ATTR ISR_enc1();
      // void IRAM_ATTR ISR_enc2();
      // void IRAM_ATTR ISR_enc3();
      // void IRAM_ATTR ISR_enc4();

      // struct to store date of encoderLeft
      myEncoder_struct encoderLeft;

      // struct to store internal libencoderLeft values
      Encoder_internal_state_t libencoderLeft;

      // struct to store date of encoderRight
      myEncoder_struct encoderRight;

      // struct to store internal libencoderRight values
      Encoder_internal_state_t libencoderRight;

      /**
       * attatch rising and falling edge interrupts to pins
      */
      void setup();

      /**
       * update counter, omega, velocity and distance of both encoder structs
      */
      void myupdate();

      /**
       * update counter, omega, velocity and distance of both encoder structs
      */
      void myupdates();

      /**
       * This encoder cant detect rotation direction by itself -> needs to be supplied
       * 
       * @param[in] encoderNum encoder number 1 or 2
      */
      //void setCntDir(unsigned int encoderNum);

      /**
       * print total driven distance to SerialPort
      */
      void printDistance();

      /**
       * update the counter variable
      */
      inline int32_t readRIGHT();
      inline int32_t readLEFT();

      /**
       * update the counter variable and reset the internal interrupt counter
      */
       int32_t readAndResetRIGHT();
       int32_t readAndResetLEFT();

       /**
       * write a certain variable p into the internal interrupt counter
       * @param[in] p variable that is written into the internal interrupt counter
      */
       inline void writeRIGHT(int32_t p);
       inline void writeLEFT(int32_t p);

       //static void update(Encoder_internal_state_t *arg);

     private:
       double updateRate;
       unsigned long previousMillis = 0;

       /**
       * calculate omega, velocity and distance of both encoder structs
       * uses elapsed time, measured counters and wheel radius
       * 
       * @param[in] encoder strcut of the encoders which shall be updated
       * @param[in] dT elapsed time since function was called the last time
      */
       void calculateValues(myEncoder_struct &encoder, double dT);
      

};

#endif

myEncoder.cpp:

#include "myEncoder.h"

#define ENCODER_ARGLIST_SIZE 4+1

static Encoder_internal_state_t *interruptArgs[ENCODER_ARGLIST_SIZE];
void update(Encoder_internal_state_t *arg);

myEncoder::myEncoder(double rate, double wheelDiameter, unsigned long countsPerRevolution, myEncoder_pins enc1pin, myEncoder_pins enc2pin)
{
  updateRate = rate;

  encoderLeft.enc.encA = enc1pin.encA;
  encoderLeft.enc.encB = enc1pin.encB;
  encoderLeft.cntPerRev = countsPerRevolution;
  encoderLeft.radius = ((wheelDiameter) / 2.0) / 1000.0; // diamter in mm to radius in m

  encoderRight.enc.encA = enc2pin.encA;
  encoderRight.enc.encB = enc2pin.encB;
  encoderRight.cntPerRev = countsPerRevolution;
  encoderRight.radius = ((wheelDiameter) / 2.0) / 1000.0; // diamter in mm to radius in m
}

myEncoder::~myEncoder(){
    
}

// interrupt service routine is volatile and can not call members of a class
// volatile long counter1;
// volatile int cntDir1 = 1;
static void IRAM_ATTR ISR_enc1()
{
  //counter1 += cntDir1;
  update(interruptArgs[1]);
}

// interrupt service routine is volatile and can not call members of a class
// volatile long counter2;
// volatile int cntDir2 = 1;
static void IRAM_ATTR ISR_enc2()
{
  //counter2 += cntDir2;
  update(interruptArgs[2]);
}

// interrupt service routine is volatile and can not call members of a class
// volatile long counter3;
// int cntDir3 = 1;
static void IRAM_ATTR ISR_enc3()
{
  //counter3 += cntDir3;
  update(interruptArgs[3]);
}

// interrupt service routine is volatile and can not call members of a class
// volatile long counter4;
// int cntDir4 = 1;
static void IRAM_ATTR ISR_enc4()
{
  //counter4 += cntDir4;
  update(interruptArgs[4]);
}

void myEncoder::setup(){
  // set pins to output
  pinMode(encoderLeft.enc.encA, INPUT_PULLUP);
  pinMode(encoderLeft.enc.encB, INPUT_PULLUP);
  pinMode(encoderRight.enc.encA, INPUT_PULLUP);
  pinMode(encoderRight.enc.encB, INPUT_PULLUP);


  libencoderLeft.pin1_register = (portInputRegister(digitalPinToPort(encoderLeft.enc.encA)));
  libencoderLeft.pin1_bitmask = (digitalPinToBitMask(encoderLeft.enc.encA));
  libencoderLeft.pin2_register = (portInputRegister(digitalPinToPort(encoderLeft.enc.encB)));
  libencoderLeft.pin2_bitmask = (digitalPinToBitMask(encoderLeft.enc.encB));
  libencoderLeft.position = 0;

  libencoderRight.pin1_register = (portInputRegister(digitalPinToPort(encoderRight.enc.encA)));
  libencoderRight.pin1_bitmask = (digitalPinToBitMask(encoderRight.enc.encA));
  libencoderRight.pin2_register = (portInputRegister(digitalPinToPort(encoderRight.enc.encB)));
  libencoderRight.pin2_bitmask = (digitalPinToBitMask(encoderRight.enc.encB));
  libencoderRight.position = 0;

  // allow time for a passive R-C filter to charge
  // through the pullup resistors, before reading
  // the initial state
  delayMicroseconds(2000);
  
  uint8_t statelibencoder1 = 0;
  if ((((*(libencoderLeft.pin1_register)) & (libencoderLeft.pin1_bitmask)) ? 1 : 0)) statelibencoder1 |= 1;
  if ((((*(libencoderLeft.pin2_register)) & (libencoderLeft.pin2_bitmask)) ? 1 : 0)) statelibencoder1 |= 2;
  libencoderLeft.state = statelibencoder1;

  uint8_t statelibencoder2 = 0;
  if ((((*(libencoderRight.pin1_register)) & (libencoderRight.pin1_bitmask)) ? 1 : 0)) statelibencoder1 |= 1;
  if ((((*(libencoderRight.pin2_register)) & (libencoderRight.pin2_bitmask)) ? 1 : 0)) statelibencoder1 |= 2;
  libencoderRight.state = statelibencoder2;

  // attatch an interrupt detector to 2 pins threough the hardware abstraction matrix
  interruptArgs[1] = &libencoderLeft;
  attachInterrupt(encoderLeft.enc.encA, ISR_enc1, CHANGE);
  interruptArgs[2] = &libencoderLeft;
  attachInterrupt(encoderLeft.enc.encB, ISR_enc2, CHANGE);
  interruptArgs[3] = &libencoderRight;
  attachInterrupt(encoderRight.enc.encA, ISR_enc3, CHANGE);
  interruptArgs[4] = &libencoderRight;
  attachInterrupt(encoderRight.enc.encB, ISR_enc4, CHANGE);
  encoderLeft.counter = 0;
  //enclib1.write(0);
  encoderRight.counter = 0;
  //enclib2.write(0);
}

void myEncoder::myupdate(){

  // measure elapsed time
  double dT = (millis() - previousMillis)/1000.0;
  if(dT > 1/updateRate){

    // update class member counter values
    encoderLeft.counter = readAndResetLEFT();
    encoderRight.counter = readAndResetRIGHT();

    // calculate w, v, distance
    calculateValues(encoderLeft, dT);
    calculateValues(encoderRight, dT);

    previousMillis = millis();
  }

}

void myEncoder::myupdates()
{

  // measure elapsed time
  double dT = (millis() - previousMillis) / 1000.0;
  if (dT > 1 / updateRate)
  {

    // update class member counter values
    encoderLeft.counter = readAndResetRIGHT();
    encoderRight.counter = readAndResetLEFT();

    // calculate w, v, distance
    calculateValues(encoderLeft, dT);
    calculateValues(encoderRight, dT);

    previousMillis = millis();
  }
}

void myEncoder::calculateValues(myEncoder_struct &encoder, double dT){

    // counter * angle resolution * radius
    encoder.distance = encoder.counter * ( (2*3.14) / encoder.cntPerRev) * encoder.radius;

    double dPhi = (encoder.counter - encoder.lastCounter) * ( (2*3.14) / encoder.cntPerRev);

    // put in array and push by 1
    for(int i = mvAvg_length-1; i >= 1; i--){
        encoder.mvAvgOmega[i] = encoder.mvAvgOmega[i-1];
    }
    encoder.mvAvgOmega[0] = dPhi/dT;

    // calculate moving avg
    encoder.omega=0;
    for(int i=0; i<mvAvg_length; i++){
        encoder.omega += encoder.mvAvgOmega[i];
    }
    encoder.omega /= mvAvg_length;

    // tangential linear velocity
    encoder.vel = encoder.omega * encoder.radius;

    encoder.lastCounter = encoder.counter;

}

// this is only usefull if you cannot determin the direction from encoders
// void myEncoder::setCntDir(unsigned int encoderNum){

//   // this sensor can detect rotation direction by itself
//   if(encoderNum == 1){

//     if (encoderLeft.counter > 0){
//       cntDir1 = 1;
//     }
//     else if (encoderLeft.counter == 0)
//     {
//       cntDir1 = 0;
//     }
//     else
//     {
//       cntDir1 = -1;
//     }
//   } else {

//     if (encoderRight.counter > 0)
//     {
//       cntDir2 = 1;
//     }
//     else if (encoderRight.counter == 0)
//     {
//       cntDir2 = 0;
//     }
//     else
//     {
//       cntDir2 = -1;
//     }
//   }

// }

void myEncoder::printDistance(){

  Serial.print("\ndsit 1 ");
  Serial.print(encoderLeft.distance);
  Serial.print("\n   dsit 2 ");
  Serial.println(encoderRight.distance);
}

inline int32_t myEncoder::readRIGHT()
{
  noInterrupts();
  update(&libencoderLeft);
  int32_t ret = libencoderLeft.position;
  interrupts();
  return ret;
}

inline int32_t myEncoder::readLEFT()
{
  noInterrupts();
  update(&libencoderRight);
  int32_t ret = libencoderRight.position;
  interrupts();
  return ret;
}

int32_t myEncoder::readAndResetRIGHT()
{
  // noInterrupts();
  update(&libencoderRight);
  int32_t ret = libencoderLeft.position;
  libencoderLeft.position = 0;
  // interrupts();
  return ret;
}

int32_t myEncoder::readAndResetLEFT()
{
  // noInterrupts();
  update(&libencoderLeft);
  int32_t ret = libencoderRight.position;
  libencoderRight.position = 0;
  // interrupts();
  return ret;
}

inline void myEncoder::writeRIGHT(int32_t p){
  noInterrupts();
  libencoderLeft.position = p;
  interrupts();
}

inline void myEncoder::writeLEFT(int32_t p)
{
  noInterrupts();
  libencoderRight.position = p;
  interrupts();
}

//                           _______         _______
//               Pin1 ______|       |_______|       |______ Pin1
// negative <---         _______         _______         __      --> positive
//               Pin2 __|       |_______|       |_______|   Pin2

//	new	new	old	old
//	pin2	pin1	pin2	pin1	Result
//	----	----	----	----	------
//	0	0	0	0	no movement
//	0	0	0	1	+1
//	0	0	1	0	-1
//	0	0	1	1	+2  (assume pin1 edges only)
//	0	1	0	0	-1
//	0	1	0	1	no movement
//	0	1	1	0	-2  (assume pin1 edges only)
//	0	1	1	1	+1
//	1	0	0	0	+1
//	1	0	0	1	-2  (assume pin1 edges only)
//	1	0	1	0	no movement
//	1	0	1	1	-1
//	1	1	0	0	+2  (assume pin1 edges only)
//	1	1	0	1	-1
//	1	1	1	0	+1
//	1	1	1	1	no movement
void update(Encoder_internal_state_t *arg)
{

  uint8_t p1val = (((*(arg->pin1_register)) & (arg->pin1_bitmask)) ? 1 : 0);
  uint8_t p2val = (((*(arg->pin2_register)) & (arg->pin2_bitmask)) ? 1 : 0);
  uint8_t state = arg->state & 3;
  if (p1val)
    state |= 4;
  if (p2val)
    state |= 8;
  arg->state = (state >> 2);
  switch (state)
  {
    case 1: case 7: case 8: case 14:
      arg->position++;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 2: case 4: case 11: case 13:
      arg->position--;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 3: case 12:
      arg->position += 2;
      //Serial.printf("position = %d\n", arg->position);
      return;
    case 6: case 9:
      arg->position -= 2;
      //Serial.printf("position = %d\n", arg->position);
      return;
  }
}

Sorry for the mess it is still under construction :).

The Timer Implementation of my own outputs the exact same error Message I already had with the lib.

CPU Frequency in MHZ:
240
Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x400d1274  PS      : 0x00060034  A0      : 0x40087894  A1      : 0x3ffbfec0
A2      : 0x00000000  A3      : 0x00000001  A4      : 0x000000ff  A5      : 0x4008d3a8
A6      : 0x00000000  A7      : 0x1300045c  A8      : 0x80081508  A9      : 0x3ff5f000
A10     : 0x3ffbdc90  A11     : 0x20000000  A12     : 0x00000400  A13     : 0x00000000
A14     : 0x3ffc65ec  A15     : 0xffffffff  SAR     : 0x00000016  EXCCAUSE: 0x00000007
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000
Core 1 was running in ISR context:
EPC1    : 0x40087aa5  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x400d1274

ELF file SHA256: 0000000000000000

Backtrace: 0x400d1274:0x3ffbfec0 0x40087891:0x3ffbfee0 0x40087aa2:0x3ffba1f0 0x40084efb:0x3ffba210 0x4008acc2:0x3ffba230
  #0  0x400d1274:0x3ffbfec0 in TimerHandler0() at src/main.cpp:235
  #1  0x40087891:0x3ffbfee0 in _xt_lowint1 at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/xtensa_vectors.S:1154
  #2  0x40087aa2:0x3ffba1f0 in spi_flash_op_block_func at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/cache_utils.c:203
  #3  0x40084efb:0x3ffba210 in ipc_task at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/ipc.c:62       
  #4  0x4008acc2:0x3ffba230 in vPortTaskWrapper at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/port.c:355 (discriminator 1)

Okay so two things: I still cannot reproduce a crash and the code is quite complex. Can you upload your whole current project to Github?

And: The Arduino-ESP32 core in the 1.0.6 version that PlatformIO uses has a bug regarding timers per Hardware timer issue with ESP32 - #11 by maxgerhardt in which they won’t fire correctly. To make timers work reliably I had to add volatile in esp32-hal-timer.c per Timer functions do not work at all in PlatformIO · Issue #5337 · espressif/arduino-esp32 · GitHub and change

the last argument of that line to false.

The Project is already on Github but not on the main branch but on this branch:
https://github.com/goldeng0d/SwarmRobotBa/tree/Reglertesten-Max

The 9600 serial baud messed with it – I changed it to 115200 and added an initial 1 second dealy and now I get a backtrace at least with the exact code you’re using.

Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
[..]
Backtrace: 0x400d0f50:0x3ffc00a0 0x40081565:0x3ffc00c0 0x40087969:0x3ffc00e0 0x40087b71:0x3ffba1f0 0x40084fd3:0x3ffba210 0x4008ad9e:0x3ffba230
  #0  0x400d0f50:0x3ffc00a0 in Drive::getEncoderValueLEFT() at src/Drive.cpp:427
  #1  0x40081565:0x3ffc00c0 in __timerISR at C:\Users\Max\.platformio\packages\framework-arduinoespressif32\cores\esp32/esp32-hal-timer.c:174
  #2  0x40087969:0x3ffc00e0 in _xt_lowint1 at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/xtensa_vectors.S:1154
  #3  0x40087b71:0x3ffba1f0 in spi_flash_op_block_func at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/spi_flash/cache_utils.c:203
  #4  0x40084fd3:0x3ffba210 in ipc_task at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/ipc.c:62
  #5  0x4008ad9e:0x3ffba230 in vPortTaskWrapper at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/port.c:355 (discriminator 1)

A thing I can definitely say is that if I add IRAM_ATTR to every function in the ISR chain and remove calls to noInterrupt(), interrupt() and update(), the thing goes through.

CPU Frequency in MHZ:
240

AP IP address: 192.168.4.1
HTTP server started

Just have to find out what the issue with update() is that makes it crash even though it’s marked as IRAM…

It 100% has something to do with the IRAM or how the compiler implements the update() function. I found that even the very first line of update() causes a crash. I replaced it with a simple “increment counter” logic and that still crashes.

What “fixes” the problem is if I follow Timer and Wifi: (Cache disabled but cached memory region accessed) (IDFGH-4322) · Issue #6164 · espressif/esp-idf · GitHub and remove the IRAM allocation flag

esp_intr_alloc(intr_source, (int)(/*ESP_INTR_FLAG_IRAM|*/ESP_INTR_FLAG_LOWMED|ESP_INTR_FLAG_EDGE), __timerISR, NULL, &intr_handle);

(in <home folder>\.platformio\packags\framework-arduinoespressif32\esp32-hal-timer.c)
so that the interrupt will simply not be running when a flash programming operation is in place.

But that should not be necessary if all routines are ISR IRAM safe per Interrupt allocation - ESP32 - — ESP-IDF Programming Guide latest documentation. I don’t see where a flash access would be coming from.

I’ll see whether I can either find the issue or reproduce it in a minimal example to ask the Arduino-ESP32 people.

OH MY GOD, the update() method does not have the IRAM attribute, I modified the incorrect function in Driver.h.

Edit: Yes that fixed it, creating PR… No, it just crashes later at a jump instruction inside update().

400810e8 <_Z6updateP24Encoder_internal_state_t>:
400810e8:       004136          entry   a1, 32
[...]
40081134:       293987          bltu    a9, a8, 40081161 <_Z6updateP24Encoder_internal_state_t+0x79>
40081137:       fcb791          l32r    a9, 40080414 <_init_end+0x14>
4008113a:       a08890          addx4   a8, a8, a9
4008113d:       0888            l32i.n  a8, a8, 0
4008113f:       0008a0          jx      a8 <-- here

It likely does not like the jump table that the switch() statement uses. :confused:

PR is open in Fix ISR routine with IRAM and no switch by maxgerhardt · Pull Request #1 · goldeng0d/SwarmRobotBa · GitHub.

Thank you very much kind stranger. I got it to work without update() and noInterrupt(), and Interrupt() is fine for me. It seemed to be a mix of monitor speed and IRAM_ATTR missing on functions especially on sei() and cli(). Although there still seems to be a problem with switch case Statements in an Interrupt function.

These macros are placebos anyway, the expand to emptiness.