pierremolinaro / acan2517

Arduino CAN driver for MCP2517FD CAN Controller (in CAN 2.0B mode)
MIT License
22 stars 10 forks source link

nCS asserted for unusually long prior to SERRIF #5

Open driftregion opened 5 years ago

driftregion commented 5 years ago

Using ESP32 with two MCP2517FD on one SPI bus, I seem to be observing a SPI contention problem. With both MCP2517 enabled, sharing a bus, with a third device injecting frames, the system reaches a state in which SERRIF is set on one of the drivers, indicating that the driver has transitioned to "restricted operation mode" (DS20005678B-page 9). This mode is reached more quickly when the bus is under heavy load.

To narrow this issue down, I disabled all but one of the MCP2517FD devices. There are no other devices on the SPI bus, apart from the ESP32.

A logic analyzer shows that the problem is correlated with the ESP taking an unusually long time to deassert nCS on one of the MCP2517 devices, indicating that one RTOS task may have preempted another.

image

I added a function to retrieve SERRIF, and called it from a 10ms task:

void check_serrif(void *)
{
    Serial.println("SERRIF checker init");
    for (int i = 0; i < 10; i ++)
    {
        digitalWrite(12, HIGH);
        vTaskDelay(100 / portTICK_PERIOD_MS);
        digitalWrite(12, LOW);
        vTaskDelay(100 / portTICK_PERIOD_MS);
    }
    Serial.println("SERRIF checker trigger pending, checking every 10ms");

    static int has_printed;
    while (1)
    {
        if (canfi_board.CAN1_serrif_is_set())
        {
            digitalWrite(12, HIGH);
            if (!has_printed)
                Serial.println("SERRIF'd");
            else
                has_printed = 1;
        }
        vTaskDelay(10 / portTICK_PERIOD_MS);
    }
}

This seems to be a heisenbug. When I added a warning inside isr_core, the problem becomes unreproduceable. (It usually triggers in a few seconds otherwise)

I'll have a closer look at how semaphores are handled, but am posting to describe what I've found in the mean-time.

pierremolinaro commented 5 years ago

Hello,

Thank you very much for your detailed report. I have read it and check my code, I have two suggestions.

First I use xSemaphoreGive in interrupt service routine ; the RTOS documentation says that xSemaphoreGiveFromISR should be used.

So, instead of

ifdef ARDUINO_ARCH_ESP32

void ACAN2517::isr (void) { xSemaphoreGive (mISRSemaphore) ; }

endif

write :

ifdef ARDUINO_ARCH_ESP32

void ACAN2517FD::isr (void) { BaseType_t xHigherPriorityTaskWoken = pdFALSE ; xSemaphoreGiveFromISR (mISRSemaphore, &xHigherPriorityTaskWoken) ; portYIELD_FROM_ISR () ; }

endif

But I am not sure this solves your problem.

The second suggestion is to disable interrupts within every beginTransaction / endTransaction block. For example: mSPI.beginTransaction (mSPISettings) ; . . . some stuff . . . mSPI.endTransaction () ;

becomes: mSPI.beginTransaction (mSPISettings) ;

ifdef ARDUINO_ARCH_ESP32

taskDISABLE_INTERRUPTS () ;

endif

  . . . some stuff . . . 

ifdef ARDUINO_ARCH_ESP32

taskENABLE_INTERRUPTS () ;

endif

mSPI.endTransaction () ;

And CS should be asserted within the disable / enable interrupt block: mSPI.beginTransaction (mSPISettings) ;

ifdef ARDUINO_ARCH_ESP32

taskDISABLE_INTERRUPTS () ;

endif

assertCS ()
  . . . some stuff . . .
deassertCS () ;

ifdef ARDUINO_ARCH_ESP32

taskENABLE_INTERRUPTS () ;

endif

mSPI.endTransaction () ;

Doing so ensures that CS will be deasserted as soon as possible.

I hope this will help you

Best regards,

Pierre Molinaro

Le 27 mai 2019 à 09:10, Nick Kirkby notifications@github.com a écrit :

Using ESP32 with two MCP2517FD on one SPI bus, I seem to be observing a SPI contention problem. With both MCP2517 enabled, sharing a bus, with a third device injecting frames, the system reaches a state in which SERRIF is set on one of the drivers, indicating that the driver has transitioned to "restricted operation mode" (DS20005678B-page 9). This mode is reached more quickly when the bus is under heavy load.

To narrow this issue down, I disabled all but one of the MCP2517FD devices. There are no other devices on the SPI bus, apart from the ESP32.

A logic analyzer shows that the problem is correlated with the ESP taking an unusually long time to deassert nCS on one of the MCP2517 devices, indicating that one RTOS task may have preempted another.

https://user-images.githubusercontent.com/20824939/58401080-bb7f6b00-8011-11e9-8011-127903d84c2a.png I added a function to retrieve SERRIF https://github.com/pierremolinaro/acan2517/compare/master...nkirkby:concurrent_access_investigation?expand=1#diff-cd9bc0c0bbd45475fb25b66825a05a2eR1066, and called it from a 10ms task:

void check_serrif(void *) { Serial.println("SERRIF checker init"); for (int i = 0; i < 10; i ++) { digitalWrite(12, HIGH); vTaskDelay(100 / portTICK_PERIOD_MS); digitalWrite(12, LOW); vTaskDelay(100 / portTICK_PERIOD_MS); } Serial.println("SERRIF checker trigger pending, checking every 10ms");

static int has_printed;
while (1)
{
    if (canfi_board.CAN1_serrif_is_set())
    {
        digitalWrite(12, HIGH);
        if (!has_printed)
            Serial.println("SERRIF'd");
        else
            has_printed = 1;
    }
    vTaskDelay(10 / portTICK_PERIOD_MS);
}

} This seems to be a heisenbug https://en.wikipedia.org/wiki/Heisenbug. When I added a warning https://github.com/pierremolinaro/acan2517/compare/master...nkirkby:concurrent_access_investigation?expand=1#diff-cd9bc0c0bbd45475fb25b66825a05a2eR714 inside isr_core, the problem becomes unreproduceable. (It usually triggers in a few seconds otherwise)

I'll have a closer look at how semaphores are handled, but am posting to describe what I've found in the mean-time.

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/pierremolinaro/acan2517/issues/5?email_source=notifications&email_token=AEWKZVGKEBSYPREACFHBULLPXOCONA5CNFSM4HPZFYYKYY3PNVWWK3TUL52HS4DFUVEXG43VMWVGG33NNVSW45C7NFSM4GV6T4WA, or mute the thread https://github.com/notifications/unsubscribe-auth/AEWKZVAOA7PMZIP3BMICJADPXOCONANCNFSM4HPZFYYA.

driftregion commented 5 years ago

Pierre, Thanks for providing a detailed response. I tried selectively adding your suggestions.

So, I tried only disabling interrupts on mINT with gpio_intr_disable(...):

bool ACAN2517::isr_core (void) {
  bool handled = false ;
  #ifdef ARDUINO_ARCH_ESP32
    gpio_intr_disable((gpio_num_t)mINT);
  #endif
  mSPI.beginTransaction (mSPISettings) ;
  const uint32_t intReg = readRegisterSPI (C1INT_REGISTER) ; // DS20005688B, page 34
  if ((intReg & (1 << 1)) != 0) { // Receive FIFO interrupt
    receiveInterrupt () ;
    handled = true ;
  }
  if ((intReg & (1 << 0)) != 0) { // Transmit FIFO interrupt
    transmitInterrupt () ;
    handled = true ;
  }
  if ((intReg & (1 << 2)) != 0) { // TBCIF interrupt
    writeByteRegisterSPI (C1INT_REGISTER, 1 << 2) ;
  }
  if ((intReg & (1 << 3)) != 0) { // MODIF interrupt
    writeByteRegisterSPI (C1INT_REGISTER, 1 << 3) ;
  }
  if ((intReg & (1 << 12)) != 0) { // SERRIF interrupt
    writeByteRegisterSPI (C1INT_REGISTER + 1, 1 << 4) ;
  }
  mSPI.endTransaction () ;
  #ifdef ARDUINO_ARCH_ESP32
    gpio_intr_enable((gpio_num_t)mINT);
  #endif
  return handled ;
}

This seems to work as expected. I'll test with both MCP2517 enabled next.

driftregion commented 5 years ago

I found that with two MCP enabled, one would preempt the other, forcing it into "restricted operation mode" I realized that we must disable interrupts for every MCP2517 on the bus during CS asserts. This seems to fix the problem.

However, this seems to have introduced another problem. For some reason, an existing interrupt is not handled when interrupts are reenabled.

driftregion commented 5 years ago

I've given up on interrupts for the time being, and am instead polling the devices at 1kHz. This seems to work well.

pierremolinaro commented 5 years ago

Hello,

I think xSemaphoreGiveFromISR should be used when called from ISR, instead of xSemaphoreGive, even if it seems to have no visible effect: it is conform to RTOS documentation. However, RTOS runs on many processors, may be there is no difference between xSemaphoreGiveFromISR and xSemaphoreGive on ESP32, I don't know.

gpio_intr_disable disables GPIO module interrupt signal, but I think it does not solve your problem: preemption may occurs between tasks, leaving a CS asserted. taskDISABLE_INTERRUPTS disables all maskable interrupts, so the MCP2517FD access sequence cannot be preempted.

I have changed xSemaphoreGive to xSemaphoreGiveFromISR and added taskDISABLE_INTERRUPTS / taskENABLE_INTERRUPTS pairs in https://github.com/pierremolinaro/acan2517-dev/blob/master/library-sources/src/ACAN2517.cpp https://github.com/pierremolinaro/acan2517-dev/blob/master/library-sources/src/ACAN2517.cpp.

Best regards,

Pierre

Le 27 mai 2019 à 21:00, Nick Kirkby notifications@github.com a écrit :

Pierre, Thanks for providing a detailed response. I tried selectively adding your suggestions.

xSemaphoreGiveFromISR seems to have no effect. The problem remains reproduceable, and the signature on the logic analyzer is identical. adding taskDISABLE_INTERRUPTS() / taskENABLE_INTERRUPTS() to only isr_core seems to have made the problem unreproduceable, however it seems to dump the core a couple times on startup before reaching a steady state -- not desirable behavior. So, I tried only disabling interrupts on mINT with gpio_intr_disable(...):

bool ACAN2517::isr_core (void) { bool handled = false ;

ifdef ARDUINO_ARCH_ESP32

gpio_intr_disable((gpio_num_t)mINT);

endif

mSPI.beginTransaction (mSPISettings) ; const uint32_t intReg = readRegisterSPI (C1INT_REGISTER) ; // DS20005688B, page 34 if ((intReg & (1 << 1)) != 0) { // Receive FIFO interrupt receiveInterrupt () ; handled = true ; } if ((intReg & (1 << 0)) != 0) { // Transmit FIFO interrupt transmitInterrupt () ; handled = true ; } if ((intReg & (1 << 2)) != 0) { // TBCIF interrupt writeByteRegisterSPI (C1INT_REGISTER, 1 << 2) ; } if ((intReg & (1 << 3)) != 0) { // MODIF interrupt writeByteRegisterSPI (C1INT_REGISTER, 1 << 3) ; } if ((intReg & (1 << 12)) != 0) { // SERRIF interrupt writeByteRegisterSPI (C1INT_REGISTER + 1, 1 << 4) ; } mSPI.endTransaction () ;

ifdef ARDUINO_ARCH_ESP32

gpio_intr_enable((gpio_num_t)mINT);

endif

return handled ; } This seems to work as expected. I'll test with both MCP2517 enabled next.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/pierremolinaro/acan2517/issues/5?email_source=notifications&email_token=AEWKZVHJFLMYH3JTEH463YTPXQVVVA5CNFSM4HPZFYYKYY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGODWKLV4Y#issuecomment-496286451, or mute the thread https://github.com/notifications/unsubscribe-auth/AEWKZVBEOT4IIG3LOIIFDX3PXQVVVANCNFSM4HPZFYYA.

driftregion commented 5 years ago

Neat! I just tried this, it seems to work well. Here I have two acan2517 on the same bus, both receiving a CAN message at the same time: image The interrupts are asserted simultaneously, and handled serially without hangups.

One question:

  1. Why is ACAN2517::available protected with mSPI.beginTransaction()/noInterrupts()? As far as I can see, it doesn't seem to involve a SPI transaction -- only a query of the driver's receive FIFO.

Thanks again. The effort you've put into building and documenting this driver is outstanding. I continue to be surprised.

pierremolinaro commented 5 years ago

Hello,

Nice ! So I can publish the new release of the library. What is the reference of your oscilloscope ?

A couple of questions:

Why is ACAN2517::available protected with mSPI.beginTransaction()/noInterrupts()? As far as I can see, it doesn't seem to involve a SPI transaction -- only a query of the driver's receive FIFO.

Yes, but the mDriverReceiveBuffer buffer is shared between two concurrent tasks, so it should be protected. More precisly, this method invoke count method that in turn reads the 32-bit mCount property. Maybe this protection is useless, it depends on how the 32-bit read access is performed by the processor. It the access is atomic, the protection is useless. I do not know the ESP32 instruction set, but I think access is atomic. On Arduino Uno, access is not atomic, it is done by four 8-bit read accesses; the protection is performed by beginTransaction / endTransaction. So for simplying, I prefer protect for all platform, even it is useless for somes. A question is about memory management for transmitted messages. ACAN2517::enterInTransmitBuffer takes a reference to a CANMessage. If mControllerTxFIFOFull (always the case when mControllerTransmitFIFOSize = 0), the CANMessage is placed in mDriverTransmitBuffer.

Yes, enterInTransmitBuffer takes a reference, but following call mDriverTransmitBuffer.append performs an object copy, not a pointer copy. No dynamic allocation here, we do not need to perform a call to free or delete.

If the caller use a heap allocated message (by new CANMessage), it is its responsability to release it after tryToSend call.

Best regards,

Pierre

Le 30 mai 2019 à 23:40, Nick Kirkby notifications@github.com a écrit :

Neat! I just tried this, it seems to work well. Here I have two acan2517 on the same bus, both receiving a CAN message at the same time: https://user-images.githubusercontent.com/20824939/58662680-a50e3380-82df-11e9-9b42-977c416dd6e1.png The interrupts are asserted simultaneously, and handled serially without hangups.

A couple of questions:

Why is ACAN2517::available protected with mSPI.beginTransaction()/noInterrupts()? As far as I can see, it doesn't seem to involve a SPI transaction -- only a query of the driver's receive FIFO.

A question is about memory management for transmitted messages. ACAN2517::enterInTransmitBuffer takes a reference to a CANMessage. If mControllerTxFIFOFull (always the case when mControllerTransmitFIFOSize = 0), the CANMessage is placed in mDriverTransmitBuffer.

If the caller allocates heap memory for the messages, they can only be sure that a message is safe to free() after the driver has successfully received mDriverTransmitBufferSize additional messages. Is this the intended usage? The existing examples (thanks for providing these!) seem to cover the cases where either:

the function calling tryToSend(frame) never returns, ensuring that frame stays in scope. or: frame is declared static I'd like to contribute an example for my use case, but I'd like to first know that the author believes it to be valid. Thanks again. The effort you've put into building and documenting this driver is outstanding. I continue to be surprised.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/pierremolinaro/acan2517/issues/5?email_source=notifications&email_token=AEWKZVHPSPTWO7LUUXA4TLDPYBCTJA5CNFSM4HPZFYYKYY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGODWTS6TA#issuecomment-497495884, or mute the thread https://github.com/notifications/unsubscribe-auth/AEWKZVGNOJT4SOV5Y36QA2TPYBCTJANCNFSM4HPZFYYA.

driftregion commented 5 years ago

Hi Pierre,

I'm using my friend's Saleae Logic Pro 8.

I had a few more problems with SPI contention between separate RTOS tasks. These seem to be fixed with the following changes (in addition to yours):

driftregion commented 5 years ago
//           mSPI.beginTransaction (mSPISettings) ;
//             #ifdef ARDUINO_ARCH_ESP32
//               taskDISABLE_INTERRUPTS () ;
//             #endif
//               assertCS () ;
//                  ... Access the MCP2517FD ...
//               deassertCS () ;
//             #ifdef ARDUINO_ARCH_ESP32
//               taskENABLE_INTERRUPTS () ;
//             #endif
//           mSPI.endTransaction () ;

Pierre, I think perhaps the order should be:

//             #ifdef ARDUINO_ARCH_ESP32
//               taskDISABLE_INTERRUPTS () ;
//             #endif
//           mSPI.beginTransaction (mSPISettings) ;
//               assertCS () ;
//                  ... Access the MCP2517FD ...
//               deassertCS () ;
//           mSPI.endTransaction () ;
//             #ifdef ARDUINO_ARCH_ESP32
//               taskENABLE_INTERRUPTS () ;
//             #endif

The reason I think that, is because of the following stacktrace, in which an interrupt is handled before endTransaction() returns:

0x4008ce80: invoke_abort at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/esp32/panic.c line 155
0x4008d0b1: abort at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/esp32/panic.c line 170
0x40089862: xQueueGiveFromISR at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/queue.c line 1299
0x40081204: ACAN2517::isr() at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 695
0x40080f7a: can1_callback() at /home/njames/Arduino/ECU/ECU.ino line 36
0x40081251: __onPinInterrupt at /opt/arduino-1.8.9/hardware/expressif/esp32/cores/esp32/esp32-hal-gpio.c line 220
0x4008a5c9: vTaskExitCritical at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/tasks.c line 4304
0x40089661: xQueueGenericSend at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/queue.c line 828
0x400dd5f1: spiEndTransaction at /opt/arduino-1.8.9/hardware/expressif/esp32/cores/esp32/esp32-hal-spi.c line 765
0x400d880e: SPIClass::endTransaction() at /opt/arduino-1.8.9/hardware/expressif/esp32/libraries/SPI/src/SPI.cpp line 143
0x400d9316: ACAN2517::available() at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 614
0x400d90b6: MCP2517FD::_get_rx_buff(CAN_FRAME&) at /home/njames/Arduino/libraries/esp32_can/src/mcp2517fd.cpp line 107
0x4014ddf7: CAN_COMMON::get_rx_buff(CAN_FRAME&) at /home/njames/Arduino/libraries/can_common/src/can_common.cpp line 133
0x400d281e: handle_incoming_frames_1kHz() at /home/njames/Arduino/ECU/ECU.ino line 106
0x400d294a: CAN_task_1kHz(void*) at /home/njames/Arduino/ECU/ECU.ino line 153
0x40088d11: vPortTaskWrapper at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/port.c line 143

I've observed that interrupts can disrupt begin() also:

0x4008ce80: invoke_abort at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/esp32/panic.c line 155
0x4008d0b1: abort at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/esp32/panic.c line 170
0x40089862: xQueueGiveFromISR at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/queue.c line 1299
0x40081204: ACAN2517::isr() at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 695
0x40080f7a: can1_callback() at /home/njames/Arduino/ECU/ECU.ino line 36
0x40081251: __onPinInterrupt at /opt/arduino-1.8.9/hardware/expressif/esp32/cores/esp32/esp32-hal-gpio.c line 220
0x400d9974: ACAN2517::writeRegister(unsigned short, unsigned int) at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 963
0x400d9b49: ACAN2517::begin(ACAN2517Settings const&, void (*)(), ACAN2517Filters const&) at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 292
0x400d9e63: ACAN2517::begin(ACAN2517Settings const&, void (*)()) at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 198
0x400d26fe: configure_MCP_CAN_controllers() at /home/njames/Arduino/ECU/ECU.ino line 47
0x400d2763: MCP_watchdog_task(void*) at /home/njames/Arduino/ECU/ECU.ino line 79
0x40088d11: vPortTaskWrapper at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/port.c line 143

After making the above change in all functions, and adding taskDISABLE_INTERRUPTS()/taskENABLE_INTERRUPTS() to begin(), I seem to have reached a point where the two driver instances no longer interfere with one another.

pierremolinaro commented 5 years ago

Hi Nick,

Thank you for the reference, I have a low-cost Salae 24MHz 8 channels, it doesn't have the same performance!

ESP32 API is not fully compatible with Arduino API, in particular SPI and interrupts are handled in a very different way. If you get run-time errors, I think it remains a race condition, and I have to study precisely what bbeginTransition / endTranssaction and taskDISABLE_INTERRUPTS / taskENABLE_INTERRUPTS actually do. I thought I did, but obviously there are still one or more mistakes.

Regards,

Pierre

Le 3 juin 2019 à 03:37, Nick Kirkby notifications@github.com a écrit :

Hi Pierre,

I'm using my friend's Saleae Logic Pro 8 https://usd.saleae.com/products/saleae-logic-pro-8?variant=7076781686844&gclid=EAIaIQobChMIkZ3Xs5DM4gIVA6vsCh3vUQA9EAQYAyABEgJc9_D_BwE.

I had a few more problems with SPI contention between separate RTOS tasks. These seem to be fixed with the following changes (in addition to yours):

using a singleton counting semaphore to grant access to isr_core using a single instance of myESP32Task to service interrupts on both driver instances diff here https://github.com/pierremolinaro/acan2517/compare/master...nkirkby:fresh_start I've not dug into this any further, as the CAN stack has reached a mostly-working state. — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/pierremolinaro/acan2517/issues/5?email_source=notifications&email_token=AEWKZVAUIJRCE5PHBHUZJK3PYRYU7A5CNFSM4HPZFYYKYY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGODWYC6VI#issuecomment-498085717, or mute the thread https://github.com/notifications/unsubscribe-auth/AEWKZVCJ543SYKWSGJASQCDPYRYU7ANCNFSM4HPZFYYA.

driftregion commented 5 years ago

Here are some relevant sources for beginTransaction from my notes:

Some findings from the last few days:

Guru Meditation Error: Core  1 panic'ed (Cache disabled but cached memory region accessed)
Core 1 register dump:
PC      : 0x400d79c0  PS      : 0x00060034  A0      : 0x80081250  A1      : 0x3ffbe780  
A2      : 0x00000000  A3      : 0x00000000  A4      : 0x3ffd1674  A5      : 0x00000000  
A6      : 0x3ffd1670  A7      : 0xffffffff  A8      : 0x80080f8c  A9      : 0x00000001  
A10     : 0x3ffcfe0c  A11     : 0x00000000  A12     : 0x3ffba2c4  A13     : 0x0000abab  
A14     : 0x00000000  A15     : 0x00060523  SAR     : 0x0000001b  EXCCAUSE: 0x00000007  
EXCVADDR: 0x00000000  LBEG    : 0x00000000  LEND    : 0x00000000  LCOUNT  : 0x00000000  
Core 1 was running in ISR context:
EPC1    : 0x40083015  EPC2    : 0x00000000  EPC3    : 0x00000000  EPC4    : 0x400d79c0

Backtrace: 0x400d79c0:0x3ffbe780 0x4008124d:0x3ffbe7a0 0x40081e45:0x3ffbe7c0 0x40083012:0x3ffba1f0 0x400846eb:0x3ffba210 0x40088acd:0x3ffba230

Rebooting...
PC: 0x400d79c0: ACAN2517::isr() at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 688
EXCVADDR: 0x00000000

Decoding stack results
0x400d79c0: ACAN2517::isr() at /home/njames/Arduino/libraries/acan2517/src/ACAN2517.cpp line 688
0x4008124d: __onPinInterrupt at /opt/arduino-1.8.9/hardware/expressif/esp32/cores/esp32/esp32-hal-gpio.c line 220
0x40083012: spi_flash_op_block_func at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/spi_flash/cache_utils.c line 82
0x400846eb: ipc_task at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/esp32/ipc.c line 62
0x40088acd: vPortTaskWrapper at /Users/ficeto/Desktop/ESP32/ESP32/esp-idf-public/components/freertos/port.c line 143
Flole998 commented 2 years ago

I believe the original issue is mentioned in the Errata-Sheet and doesn't exist on the MCP2518FD anymore. For reference: https://ww1.microchip.com/downloads/en/DeviceDoc/MCP2517FD-Silicon-Errata-and-Data-Sheet-Clarification-DS80000792C.pdf