analogRead causes ESP32 Core 1 panic and reboot

Hello

First time posting and I’m new to SimpleFOC. I am trying to run SimpleFOC (2.2.2) on an Uncle Ali ESP32 board. I have my project set up and compiling using PlatformIO.

I have a very simple program that does some SimpleFOC initialization, and in the main loop tries to do an analogRead of pin 4, but this causes the program to crash unexpectedly and forces the ESP32 to reboot. I noticed that this crash only occurs if I initialize the LowsideCurrentSense object (in my code: cs.init()).

I’m attaching to this post the code and stack trace below. I haven’t got a ESP prog board (or similar) so I’ve not been able to do any further debugging.

I’m not very familiar with SimpleFOC’s internals, or ESP32 in general, but I was wondering if perhaps there is a bug in SimpleFOC? The reason why I think it might be a bug in SimpleFOC (or - more likely - my misuse of the library) is because I am able to analogRead pin 4 and log to console without the LowsideCurrentSense stuff.

My platformio.ini file contains the following:

[env:esp32dev]
platform = espressif32
board = esp32dev
framework = arduino
monitor_speed = 115200
monitor_filters = log2file
lib_deps = 
	SPI
	Wire
	askuric/Simple FOC@^2.2.2
lib_archive = false

Here is the code I’m running:

#include <Arduino.h>
#include <SimpleFOC.h>

// DRV8302 pins connections
// don't forget to connect the common ground pin
#define INH_A 21
#define INH_B 19
#define INH_C 18
#define EN_GATE 5
#define M_PWM 25
#define M_OC 26
#define OC_ADJ 12
#define OC_GAIN 14
#define IOUTA 34
#define IOUTB 35
#define IOUTC 32
// Motor instance
BLDCMotor motor = BLDCMotor(15);
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);

// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);

// encoder instance
Encoder encoder = Encoder(22, 23, 1024);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}

void setup() {
  Serial.begin(115200);
  // initialize encoder sensor hardware
  encoder.init();
  encoder.enableInterrupts(doA, doB);
  // link the motor to the sensor
  motor.linkSensor(&encoder);
  // DRV8302 specific code
  // M_OC  - enable overcurrent protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);
  // M_PWM  - enable 3pwm mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,HIGH);
  // OD_ADJ - set the maximum overcurrent limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  pinMode(OC_GAIN,OUTPUT);
  digitalWrite(OC_GAIN,LOW);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 24;
  driver.pwm_frequency = 15000;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  cs.linkDriver(&driver);
  // align voltage
  motor.voltage_sensor_align = 1.0;
  // control loop type and torque mode
  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller = MotionControlType::torque;
  motor.motion_downsample = 0.0;
  // velocity loop PID
  motor.PID_velocity.P = 0.5;
  motor.PID_velocity.I = 5.0;
  // Low pass filtering time constant
  motor.LPF_velocity.Tf = 0.02;
  // angle loop PID
  motor.P_angle.P = 20.0;
  // Low pass filtering time constant
  motor.LPF_angle.Tf = 0.0;
  // current q loop PID
  motor.PID_current_q.P = 1.0;
  motor.PID_current_q.I = 200.0;
  // Low pass filtering time constant
  motor.LPF_current_q.Tf = 0.01;
  // current d loop PID
  motor.PID_current_d.P = 1.0;
  motor.PID_current_d.I = 200.0;
  // Low pass filtering time constant
  motor.LPF_current_d.Tf = 0.01;
  // Limits
  motor.velocity_limit = 15.0; // 100 rad/s velocity limit
  motor.voltage_limit = 23.0;   // 12 Volt limit
  motor.current_limit = 10.0;    // 2 Amp current limit
  // use monitoring with serial for motor init
  // initialise motor
  motor.init();

  // including this line causes the ESP32 to crash:
  cs.init();
}

void loop() {
  // Very simply trying to read pin 4 and print the value to the console.
  float num = analogRead(4);
  Serial.println(num);
}

The following code block contains the entire stack trace:

Guru Meditation Error: Core  1 panic'ed (Interrupt wdt timeout on CPU1). 

Core  1 register dump:
PC      : 0x40081331  PS      : 0x00060035  A0      : 0x80081448  A1      : 0x3ffbf0dc  
A2      : 0x3ff48854  A3      : 0x00010000  A4      : 0x82060022  A5      : 0x0000000c  
A6      : 0x3ffc1d20  A7      : 0x00000000  A8      : 0x82070022  A9      : 0x80050022  
A10     : 0x3ffc1600  A11     : 0x00000001  A12     : 0x800848b8  A13     : 0x3ffb2720  
A14     : 0x3ffc1d20  A15     : 0x00000001  SAR     : 0x0000001a  EXCCAUSE: 0x00000006  
EXCVADDR: 0x00000000  LBEG    : 0x400d501e  LEND    : 0x400d502a  LCOUNT  : 0x00000003  
Core  1 was running in ISR context:
EPC1    : 0x400df2a7  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x00000000


Backtrace:0x4008132e:0x3ffbf0dc |<-CORRUPTED


Core  0 register dump:
PC      : 0x400f316a  PS      : 0x00060535  A0      : 0x800de099  A1      : 0x3ffbd2b0  
A2      : 0x00000000  A3      : 0x40085790  A4      : 0x00060520  A5      : 0x3ffbcab0  
A6      : 0x007bf138  A7      : 0x003fffff  A8      : 0x800ddcbe  A9      : 0x3ffbd280  
A10     : 0x00000000  A11     : 0x3ffbf134  A12     : 0x3ffbf134  A13     : 0x00000000  
A14     : 0x00060520  A15     : 0x00000000  SAR     : 0x0000001a  EXCCAUSE: 0x00000006  
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000  


Backtrace:0x400f3167:0x3ffbd2b00x400de096:0x3ffbd2d0 0x400890b5:0x3ffbd2f0 




ELF file SHA256: 0000000000000000

Rebooting...
ets Jun  8 2016 00:22:57

rst:0xc (SW_CPU_RESET),boot:0x13 (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:2
load:0x3fff0030,len:1184
load:0x40078000,len:12784
load:0x40080400,len:3032
entry 0x400805e4
Guru Meditation Error: Core  1 panic'ed (Interrupt wdt timeout on CPU1). 

Core  1 register dump:
PC      : 0x40081331  PS      : 0x00060035  A0      : 0x80081448  A1      : 0x3ffbf0dc  
A2      : 0x3ff48854  A3      : 0x00010000  A4      : 0x82060027  A5      : 0x0000000c  
A6      : 0x3ffc1d20  A7      : 0x00000000  A8      : 0x82070027  A9      : 0x80050027  
A10     : 0x3ffc1600  A11     : 0x00000001  A12     : 0x800848b8  A13     : 0x3ffb2720  
A14     : 0x3ffc1d20  A15     : 0x00000001  SAR     : 0x0000001a  EXCCAUSE: 0x00000006  
EXCVADDR: 0x00000000  LBEG    : 0x400d501e  LEND    : 0x400d502a  LCOUNT  : 0x00000003  
Core  1 was running in ISR context:
EPC1    : 0x400df2a7  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x00000000


Backtrace:0x4008132e:0x3ffbf0dc |<-CORRUPTED


Core  0 register dump:
PC      : 0x400f316a  PS      : 0x00060535  A0      : 0x800de099  A1      : 0x3ffbd2b0  
A2      : 0x00000000  A3      : 0x40085790  A4      : 0x00060520  A5      : 0x3ffbcab0  
A6      : 0x007bf138  A7      : 0x003fffff  A8      : 0x800ddcbe  A9      : 0x3ffbd280  
A10     : 0x00000000  A11     : 0x3ffbf134  A12     : 0x3ffbf134  A13     : 0x00000000  
A14     : 0x00060520  A15     : 0x00000000  SAR     : 0x0000001a  EXCCAUSE: 0x00000006  
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000  


Backtrace:0x400f3167:0x3ffbd2b00x400de096:0x3ffbd2d0 0x400890b5:0x3ffbd2f0 




ELF file SHA256: 0000000000000000

Thanks for your help!

Hey @chillel,

This is probably related