usb and sdcard sharing improvements

* Add traceback after watchdog timeout

Add the cpability to perform a traceback following a watchdog timeout.

* Enhanced hardware SPI

Allow use of either SSP0 or SSP1.
Ensure that no data is left in I/O buffers after calls to enable sharing of SSP hardware.

* Make flash emulation of eeprom the default

Make use of flash for eeprom storage the default. This means that usage of eeprom will not cause USB drive mount/unmount operations.

* Allow sharing of SD card

SD card I/O operations from the USB stack take place in idle loop, rather than at interrupt time. Allowing sharing of the SPI bus.

New configuration options to allow usage of the SD card to be specified.

* Fix problem with hardware SPI pins
This commit is contained in:
Andy Shaw
2018-09-19 18:33:20 +01:00
committed by Christopher Pepper
parent 5ddf52d58e
commit 870bfd08f5
14 changed files with 527 additions and 77 deletions

View File

@ -0,0 +1,318 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifdef TARGET_LPC1768
#include "../../core/macros.h"
#include "../../core/serial.h"
#include <stdarg.h>
#include "../shared/backtrace/unwinder.h"
#include "../shared/backtrace/unwmemaccess.h"
#include "watchdog.h"
#include <debug_frmwrk.h>
// Debug monitor that dumps to the Programming port all status when
// an exception or WDT timeout happens - And then resets the board
// All the Monitor routines must run with interrupts disabled and
// under an ISR execution context. That is why we cannot reuse the
// Serial interrupt routines or any C runtime, as we don't know the
// state we are when running them
// A SW memory barrier, to ensure GCC does not overoptimize loops
#define sw_barrier() __asm__ volatile("": : :"memory");
// (re)initialize UART0 as a monitor output to 250000,n,8,1
static void TXBegin(void) {
}
// Send character through UART with no interrupts
static void TX(char c) {
_DBC(c);
}
// Send String through UART
static void TX(const char* s) {
while (*s) TX(*s++);
}
static void TXDigit(uint32_t d) {
if (d < 10) TX((char)(d+'0'));
else if (d < 16) TX((char)(d+'A'-10));
else TX('?');
}
// Send Hex number thru UART
static void TXHex(uint32_t v) {
TX("0x");
for (uint8_t i = 0; i < 8; i++, v <<= 4)
TXDigit((v >> 28) & 0xF);
}
// Send Decimal number thru UART
static void TXDec(uint32_t v) {
if (!v) {
TX('0');
return;
}
char nbrs[14];
char *p = &nbrs[0];
while (v != 0) {
*p++ = '0' + (v % 10);
v /= 10;
}
do {
p--;
TX(*p);
} while (p != &nbrs[0]);
}
// Dump a backtrace entry
static bool UnwReportOut(void* ctx, const UnwReport* bte) {
int* p = (int*)ctx;
(*p)++;
TX('#'); TXDec(*p); TX(" : ");
TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function);
TX('+'); TXDec(bte->address - bte->function);
TX(" PC:");TXHex(bte->address); TX('\n');
return true;
}
#ifdef UNW_DEBUG
void UnwPrintf(const char* format, ...) {
char dest[256];
va_list argptr;
va_start(argptr, format);
vsprintf(dest, format, argptr);
va_end(argptr);
TX(&dest[0]);
}
#endif
/* Table of function pointers for passing to the unwinder */
static const UnwindCallbacks UnwCallbacks = {
UnwReportOut,
UnwReadW,
UnwReadH,
UnwReadB
#if defined(UNW_DEBUG)
,UnwPrintf
#endif
};
/**
* HardFaultHandler_C:
* This is called from the HardFault_HandlerAsm with a pointer the Fault stack
* as the parameter. We can then read the values from the stack and place them
* into local variables for ease of reading.
* We then read the various Fault Status and Address Registers to help decode
* cause of the fault.
* The function ends with a BKPT instruction to force control back into the debugger
*/
extern "C"
void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) {
static const char* causestr[] = {
"NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
};
UnwindFrame btf;
// Dump report to the Programming port (interrupts are DISABLED)
TXBegin();
TX("\n\n## Software Fault detected ##\n");
TX("Cause: "); TX(causestr[cause]); TX('\n');
TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n');
TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n');
TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n');
TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n');
TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n');
TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n');
TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n');
TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n');
// Configurable Fault Status Register
// Consists of MMSR, BFSR and UFSR
TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n');
// Hard Fault Status Register
TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n');
// Debug Fault Status Register
TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n');
// Auxiliary Fault Status Register
TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n');
// Read the Fault Address Registers. These may not contain valid values.
// Check BFARVALID/MMARVALID to see if they are valid values
// MemManage Fault Address Register
TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n');
// Bus Fault Address Register
TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n');
TX("ExcLR: "); TXHex(lr); TX('\n');
TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n');
btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer
btf.fp = btf.sp;
btf.lr = ((unsigned long)sp[5]);
btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it
// Perform a backtrace
TX("\nBacktrace:\n\n");
int ctr = 0;
UnwindStart(&btf, &UnwCallbacks, &ctr);
// Disable all NVIC interrupts
NVIC->ICER[0] = 0xFFFFFFFF;
NVIC->ICER[1] = 0xFFFFFFFF;
// Relocate VTOR table to default position
SCB->VTOR = 0;
// Clear cause of reset to prevent entering smoothie bootstrap
HAL_clear_reset_source();
// Restart watchdog
//WDT_Restart(WDT);
watchdog_init();
// Reset controller
NVIC_SystemReset();
while(1) { watchdog_init(); }
}
extern "C" {
__attribute__((naked)) void NMI_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#0")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void HardFault_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#1")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void MemManage_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#2")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void BusFault_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#3")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void UsageFault_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#4")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void DebugMon_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#5")
A("b HardFault_HandlerC")
);
}
/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
__attribute__((naked)) void WDT_IRQHandler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#6")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void RSTC_Handler(void) {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#7")
A("b HardFault_HandlerC")
);
}
}
#endif // ARDUINO_ARCH_SAM

View File

@ -152,4 +152,7 @@ using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
#define HAL_IDLETASK 1
void HAL_idletask(void);
#endif // _HAL_LPC1768_H_

View File

@ -49,7 +49,6 @@
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
@ -59,7 +58,6 @@
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
#if ENABLED(LPC_SOFTWARE_SPI)
#include "SoftwareSPI.h"
@ -127,8 +125,25 @@
#include <lpc17xx_ssp.h>
#include <lpc17xx_clkpwr.h>
void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0
// decide which HW SPI device to use
#ifndef LPC_HW_SPI_DEV
#if (SCK_PIN == P0_07 && MISO_PIN == P0_08 && MOSI_PIN == P0_09)
#define LPC_HW_SPI_DEV 1
#else
#if (SCK_PIN == P0_15 && MISO_PIN == P0_17 && MOSI_PIN == P0_18)
#define LPC_HW_SPI_DEV 0
#else
#error "Invalid pins selected for hardware SPI"
#endif
#endif
#endif
#if (LPC_HW_SPI_DEV == 0)
#define LPC_SSPn LPC_SSP0
#else
#define LPC_SSPn LPC_SSP1
#endif
void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0
PINSEL_CFG_Type PinCfg; // data structure to hold init values
PinCfg.Funcnum = 2;
PinCfg.OpenDrain = 0;
@ -147,10 +162,13 @@
PinCfg.Portnum = LPC1768_PIN_PORT(MOSI_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_OUTPUT(MOSI_PIN);
// divide PCLK by 2 for SSP0
CLKPWR_SetPCLKDiv(LPC_HW_SPI_DEV == 0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2);
spiInit(0);
SSP_Cmd(LPC_SSPn, ENABLE); // start SSP running
}
void spiInit(uint8_t spiRate) {
SSP_Cmd(LPC_SSP0, DISABLE); // Disable SSP0 before changing rate
// table to convert Marlin spiRates (0-5 plus default) into bit rates
uint32_t Marlin_speed[7]; // CPSR is always 2
Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED
@ -160,33 +178,32 @@
Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5
Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6
Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h
// divide PCLK by 2 for SSP0
CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_SSP0, CLKPWR_PCLKSEL_CCLK_DIV_2);
// setup for SPI mode
SSP_CFG_Type HW_SPI_init; // data structure to hold init values
SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode
HW_SPI_init.ClockRate = Marlin_speed[MIN(spiRate, 6)]; // put in the specified bit rate
SSP_Init(LPC_SSP0, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers
HW_SPI_init.Mode |= SSP_CR1_SSP_EN;
SSP_Init(LPC_SSPn, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers
}
SSP_Cmd(LPC_SSP0, ENABLE); // start SSP0 running
static uint8_t doio(uint8_t b) {
/* send and receive a single byte */
SSP_SendData(LPC_SSPn, b & 0x00FF);
while (SSP_GetStatus(LPC_SSPn, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSPn) & 0x00FF;
}
void spiSend(uint8_t b) {
while (!SSP_GetStatus(LPC_SSP0, SSP_STAT_TXFIFO_NOTFULL)); // wait for room in the buffer
SSP_SendData(LPC_SSP0, b & 0x00FF);
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
doio(b);
}
void spiSend(const uint8_t* buf, size_t n) {
if (n == 0) return;
for (uint16_t i = 0; i < n; i++) {
while (!SSP_GetStatus(LPC_SSP0, SSP_STAT_TXFIFO_NOTFULL)); // wait for room in the buffer
SSP_SendData(LPC_SSP0, buf[i] & 0x00FF);
doio(buf[i]);
}
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
}
void spiSend(uint32_t chan, byte b) {
@ -195,17 +212,9 @@
void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
}
static uint8_t get_one_byte() {
// send a dummy byte so can clock in receive data
SSP_SendData(LPC_SSP0,0x00FF);
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
}
// Read single byte from SPI
uint8_t spiRec() {
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
return get_one_byte();
return doio(0xff);
}
uint8_t spiRec(uint32_t chan) {
@ -214,22 +223,25 @@
// Read from SPI into buffer
void spiRead(uint8_t*buf, uint16_t nbyte) {
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
if (nbyte == 0) return;
for (int i = 0; i < nbyte; i++) {
buf[i] = get_one_byte();
buf[i] = doio(0xff);
}
}
static uint8_t spiTransfer(uint8_t b) {
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
SSP_SendData(LPC_SSP0, b); // send the byte
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
return doio(b);
}
// Write from buffer to SPI
void spiSendBlock(uint8_t token, const uint8_t* buf) {
uint8_t response;
response = spiTransfer(token);
for (uint16_t i = 0; i < 512; i++) {
response = spiTransfer(buf[i]);
}
UNUSED(response);
}
/** Begin SPI transaction, set clock, bit order, data mode */
@ -270,4 +282,3 @@ uint16_t SPIClass::transfer16(uint16_t data) {
SPIClass SPI;
#endif // TARGET_LPC1768

View File

@ -39,19 +39,19 @@
#define USEABLE_HARDWARE_PWM(pin) useable_hardware_PWM(pin)
#define LPC_PIN(pin) (gpio_pin(pin))
#define LPC_GPIO(port) (gpio_port(port))
#define LPC_PIN(pin) gpio_pin(pin)
#define LPC_GPIO(port) gpio_port(port)
#define SET_DIR_INPUT(IO) (gpio_set_input(IO))
#define SET_DIR_OUTPUT(IO) (gpio_set_output(IO))
#define SET_DIR_INPUT(IO) gpio_set_input(IO)
#define SET_DIR_OUTPUT(IO) gpio_set_output(IO)
#define SET_MODE(IO, mode) (pinMode(IO, mode))
#define SET_MODE(IO, mode) pinMode(IO, mode)
#define WRITE_PIN_SET(IO) (gpio_set(IO))
#define WRITE_PIN_CLR(IO) (gpio_clear(IO))
#define WRITE_PIN_SET(IO) gpio_set(IO)
#define WRITE_PIN_CLR(IO) gpio_clear(IO)
#define READ_PIN(IO) (gpio_get(IO))
#define WRITE_PIN(IO,V) (gpio_set(IO, V))
#define READ_PIN(IO) gpio_get(IO)
#define WRITE_PIN(IO,V) gpio_set(IO, V)
/**
* Magic I/O routines

View File

@ -9,7 +9,13 @@
#include <usb/cdcuser.h>
#include <usb/mscuser.h>
#include <CDCSerial.h>
#include <usb/mscuser.h>
extern "C" {
#include <debug_frmwrk.h>
}
#include "../../sd/cardreader.h"
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "HAL_timers.h"
@ -41,15 +47,28 @@ void HAL_init() {
delay(100);
}
#endif
(void)MSC_SD_Init(0);
USB_Init();
//debug_frmwrk_init();
//_DBG("\n\nDebug running\n");
// Initialise the SD card chip select pins as soon as possible
#ifdef SS_PIN
digitalWrite(SS_PIN, HIGH);
pinMode(SS_PIN, OUTPUT);
#endif
#ifdef ONBOARD_SD_CS
digitalWrite(ONBOARD_SD_CS, HIGH);
pinMode(ONBOARD_SD_CS, OUTPUT);
#endif
USB_Init(); // USB Initialization
USB_Connect(FALSE); // USB clear connection
delay(1000); // Give OS time to notice
USB_Connect(TRUE);
#ifndef USB_SD_DISABLED
MSC_SD_Init(0); // Enable USB SD card access
#endif
const uint32_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50);
HAL_idletask();
#if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash quickly during USB initialization
#endif
@ -68,4 +87,23 @@ void HAL_init() {
LPC1768_PWM_init();
}
// HAL idle task
void HAL_idletask(void) {
#if ENABLED(SDSUPPORT) && defined(SHARED_SD_CARD)
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING and IS_SD_FILE_OPEN to check for access but
// this will not reliably detect delete operations. To be safe we will lock
// the disk if Marlin has it mounted. Unfortuately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING || IS_SD_FILE_OPEN)
if (card.cardOK)
MSC_Aquire_Lock();
else
MSC_Release_Lock();
#endif
// Perform USB stack housekeeping
MSC_RunDeferredCommands();
}
#endif // TARGET_LPC1768

View File

@ -21,4 +21,4 @@
*/
#include "../shared/persistent_store_api.h"
//#define FLASH_EEPROM
#define FLASH_EEPROM

View File

@ -116,7 +116,7 @@ bool PersistentStore::access_finish() {
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (int i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
for (size_t i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
eeprom_dirty = true;
crc16(crc, value, size);
pos += size;
@ -125,7 +125,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
if (writing) for (int i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
crc16(crc, buff, size);
pos += size;
return false; // return true for any error

View File

@ -50,7 +50,8 @@
#ifndef SS_PIN
#define SS_PIN P1_23
#endif
#ifndef SDSS
#if !defined(SDSS) || SDSS == P_NC // get defaulted in pins.h
#undef SDSS
#define SDSS SS_PIN
#endif

View File

@ -63,6 +63,7 @@
#include "SoftwareSPI.h"
#include "../../shared/Delay.h"
#undef SPI_SPEED
#define SPI_SPEED 3 // About 1 MHz
static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL;

View File

@ -62,6 +62,7 @@
#include <U8glib.h>
#include "SoftwareSPI.h"
#undef SPI_SPEED
#define SPI_SPEED 2 // About 2 MHz
static uint8_t SPI_speed = 0;

View File

@ -30,7 +30,29 @@
#include "watchdog.h"
void watchdog_init(void) {
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
#if ENABLED(WATCHDOG_RESET_MANUAL)
// We enable the watchdog timer, but only for the interrupt.
// Configure WDT to only trigger an interrupt
// Disable WDT interrupt (just in case, to avoid triggering it!)
NVIC_DisableIRQ(WDT_IRQn);
// We NEED memory barriers to ensure Interrupts are actually disabled!
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
__DSB();
__ISB();
// Configure WDT to only trigger an interrupt
// Initialize WDT with the given parameters
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY);
// Configure and enable WDT interrupt.
NVIC_ClearPendingIRQ(WDT_IRQn);
NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
NVIC_EnableIRQ(WDT_IRQn);
#else
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
#endif
WDT_Start(WDT_TIMEOUT);
}