Various fixes for DUE... (#10152)
- Watchdog reset during SD Card initialization. - Move `DebugMonitor` to `DebugMonitor_Due.cpp`. - Since the watchdog is enabled on boot do extra resets during init. - Have `thermalManager` do watchdog reset before its ISR starts to prevent reset. - Ensure that timers are stopped before reprogramming them to address tone issues. - Improve SAM3XE reset when reflashed through the native port.
This commit is contained in:
parent
c3c264978f
commit
97e8a6ebd9
238
Marlin/src/HAL/HAL_DUE/DebugMonitor_Due.cpp
Normal file
238
Marlin/src/HAL/HAL_DUE/DebugMonitor_Due.cpp
Normal file
|
@ -0,0 +1,238 @@
|
||||||
|
/**
|
||||||
|
* 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 ARDUINO_ARCH_SAM
|
||||||
|
|
||||||
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
#include "../../Marlin.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) {
|
||||||
|
|
||||||
|
// Disable UART interrupt in NVIC
|
||||||
|
NVIC_DisableIRQ( UART_IRQn );
|
||||||
|
|
||||||
|
// Disable clock
|
||||||
|
pmc_disable_periph_clk( ID_UART );
|
||||||
|
|
||||||
|
// Configure PMC
|
||||||
|
pmc_enable_periph_clk( ID_UART );
|
||||||
|
|
||||||
|
// Disable PDC channel
|
||||||
|
UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
|
||||||
|
|
||||||
|
// Reset and disable receiver and transmitter
|
||||||
|
UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
|
||||||
|
|
||||||
|
// Configure mode: 8bit, No parity, 1 bit stop
|
||||||
|
UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
|
||||||
|
|
||||||
|
// Configure baudrate (asynchronous, no oversampling) to 250000 bauds
|
||||||
|
UART->UART_BRGR = (SystemCoreClock / (250000 << 4));
|
||||||
|
|
||||||
|
// Enable receiver and transmitter
|
||||||
|
UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Send character through UART with no interrupts
|
||||||
|
static void TX(char c) {
|
||||||
|
while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); };
|
||||||
|
UART->UART_THR = 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 (int i=0; i<8; i++, v <<= 4) {
|
||||||
|
TXDigit((v >> 28) & 0xF);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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 *hardfault_args, unsigned long cause) {
|
||||||
|
|
||||||
|
static const char* causestr[] = {
|
||||||
|
"NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
|
||||||
|
};
|
||||||
|
|
||||||
|
// 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)hardfault_args[0])); TX('\n');
|
||||||
|
TX("R1 : "); TXHex(((unsigned long)hardfault_args[1])); TX('\n');
|
||||||
|
TX("R2 : "); TXHex(((unsigned long)hardfault_args[2])); TX('\n');
|
||||||
|
TX("R3 : "); TXHex(((unsigned long)hardfault_args[3])); TX('\n');
|
||||||
|
TX("R12 : "); TXHex(((unsigned long)hardfault_args[4])); TX('\n');
|
||||||
|
TX("LR : "); TXHex(((unsigned long)hardfault_args[5])); TX('\n');
|
||||||
|
TX("PC : "); TXHex(((unsigned long)hardfault_args[6])); TX('\n');
|
||||||
|
TX("PSR : "); TXHex(((unsigned long)hardfault_args[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');
|
||||||
|
|
||||||
|
// Reset controller
|
||||||
|
NVIC_SystemReset();
|
||||||
|
while(1) { WDT_Restart(WDT); }
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void NMI_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#0 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void HardFault_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#1 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void MemManage_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#2 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void BusFault_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#3 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void UsageFault_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#4 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void DebugMon_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#5 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void WDT_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#6 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__((naked)) void RSTC_Handler(void) {
|
||||||
|
__asm volatile (
|
||||||
|
" tst lr, #4 \n"
|
||||||
|
" ite eq \n"
|
||||||
|
" mrseq r0, msp \n"
|
||||||
|
" mrsne r0, psp \n"
|
||||||
|
" mov r1,#7 \n"
|
||||||
|
" b HardFault_HandlerC \n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
|
@ -34,6 +34,7 @@
|
||||||
#include "../HAL.h"
|
#include "../HAL.h"
|
||||||
|
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
|
#include "usb/usb_task.h"
|
||||||
|
|
||||||
// --------------------------------------------------------------------------
|
// --------------------------------------------------------------------------
|
||||||
// Externals
|
// Externals
|
||||||
|
@ -73,6 +74,18 @@ uint16_t HAL_adc_result;
|
||||||
// Public functions
|
// Public functions
|
||||||
// --------------------------------------------------------------------------
|
// --------------------------------------------------------------------------
|
||||||
|
|
||||||
|
// HAL initialization task
|
||||||
|
void HAL_init(void) {
|
||||||
|
// Initialize the USB stack
|
||||||
|
usb_task_init();
|
||||||
|
}
|
||||||
|
|
||||||
|
// HAL idle task
|
||||||
|
void HAL_idletask(void) {
|
||||||
|
// Perform USB stack housekeeping
|
||||||
|
usb_task_idle();
|
||||||
|
}
|
||||||
|
|
||||||
// disable interrupts
|
// disable interrupts
|
||||||
void cli(void) { noInterrupts(); }
|
void cli(void) { noInterrupts(); }
|
||||||
|
|
||||||
|
@ -82,14 +95,13 @@ void sei(void) { interrupts(); }
|
||||||
void HAL_clear_reset_source(void) { }
|
void HAL_clear_reset_source(void) { }
|
||||||
|
|
||||||
uint8_t HAL_get_reset_source(void) {
|
uint8_t HAL_get_reset_source(void) {
|
||||||
switch ((RSTC->RSTC_SR >> 8) & 7) {
|
switch ((RSTC->RSTC_SR >> 8) & 0x07) {
|
||||||
case 0: return RST_POWER_ON; break;
|
case 0: return RST_POWER_ON;
|
||||||
case 1: return RST_BACKUP; break;
|
case 1: return RST_BACKUP;
|
||||||
case 2: return RST_WATCHDOG; break;
|
case 2: return RST_WATCHDOG;
|
||||||
case 3: return RST_SOFTWARE; break;
|
case 3: return RST_SOFTWARE;
|
||||||
case 4: return RST_EXTERNAL; break;
|
case 4: return RST_EXTERNAL;
|
||||||
default:
|
default: return 0;
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -160,14 +160,15 @@ void toneInit();
|
||||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
|
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
|
||||||
void noTone(const pin_t _pin);
|
void noTone(const pin_t _pin);
|
||||||
|
|
||||||
// Enable hooks into idle and setup for USB stack
|
// Enable hooks into idle and setup for HAL
|
||||||
#define HAL_IDLETASK 1
|
#define HAL_IDLETASK 1
|
||||||
#define HAL_INIT 1
|
#define HAL_INIT 1
|
||||||
|
void HAL_idletask(void);
|
||||||
|
void HAL_init(void);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#endif
|
#endif
|
||||||
void HAL_idletask(void);
|
|
||||||
void HAL_init(void);
|
|
||||||
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
|
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
|
|
@ -96,6 +96,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||||
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
|
||||||
uint32_t channel = TimerConfig[timer_num].channel;
|
uint32_t channel = TimerConfig[timer_num].channel;
|
||||||
|
|
||||||
|
// Disable interrupt, just in case it was already enabled
|
||||||
|
NVIC_DisableIRQ(irq);
|
||||||
|
|
||||||
|
// Disable timer interrupt
|
||||||
|
tc->TC_CHANNEL[channel].TC_IDR = TC_IDR_CPCS;
|
||||||
|
|
||||||
|
// Stop timer, just in case, to be able to reconfigure it
|
||||||
|
TC_Stop(tc, channel);
|
||||||
|
|
||||||
pmc_set_writeprotect(false);
|
pmc_set_writeprotect(false);
|
||||||
pmc_enable_periph_clk((uint32_t)irq);
|
pmc_enable_periph_clk((uint32_t)irq);
|
||||||
NVIC_SetPriority(irq, TimerConfig [timer_num].priority);
|
NVIC_SetPriority(irq, TimerConfig [timer_num].priority);
|
||||||
|
@ -103,12 +112,16 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||||
// wave mode, reset counter on match with RC,
|
// wave mode, reset counter on match with RC,
|
||||||
TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
|
TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
|
||||||
|
|
||||||
|
// Set compare value
|
||||||
TC_SetRC(tc, channel, VARIANT_MCK / 2 / frequency);
|
TC_SetRC(tc, channel, VARIANT_MCK / 2 / frequency);
|
||||||
|
|
||||||
|
// And start timer
|
||||||
TC_Start(tc, channel);
|
TC_Start(tc, channel);
|
||||||
|
|
||||||
// enable interrupt on RC compare
|
// enable interrupt on RC compare
|
||||||
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPCS;
|
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPCS;
|
||||||
|
|
||||||
|
// Finally, enable IRQ
|
||||||
NVIC_EnableIRQ(irq);
|
NVIC_EnableIRQ(irq);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -109,23 +109,12 @@ FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||||
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
|
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
|
||||||
}
|
}
|
||||||
|
|
||||||
FORCE_INLINE static void HAL_timer_set_count(const uint8_t timer_num, const hal_timer_t counter) {
|
|
||||||
const tTimerConfig * const pConfig = &TimerConfig[timer_num];
|
|
||||||
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV = counter;
|
|
||||||
}
|
|
||||||
|
|
||||||
// if counter too high then bump up compare
|
// if counter too high then bump up compare
|
||||||
FORCE_INLINE static void HAL_timer_restrain(const uint8_t timer_num, const uint16_t interval_ticks) {
|
FORCE_INLINE static void HAL_timer_restrain(const uint8_t timer_num, const uint16_t interval_ticks) {
|
||||||
const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
|
const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
|
||||||
if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_compare(timer_num, mincmp);
|
if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_compare(timer_num, mincmp);
|
||||||
}
|
}
|
||||||
|
|
||||||
// if counter too high then clear it
|
|
||||||
FORCE_INLINE static void HAL_timer_restrain_count(const uint8_t timer_num, const uint16_t interval_ticks) {
|
|
||||||
const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
|
|
||||||
if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_count(timer_num, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
void HAL_timer_enable_interrupt(const uint8_t timer_num);
|
void HAL_timer_enable_interrupt(const uint8_t timer_num);
|
||||||
void HAL_timer_disable_interrupt(const uint8_t timer_num);
|
void HAL_timer_disable_interrupt(const uint8_t timer_num);
|
||||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
|
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
|
||||||
|
|
|
@ -33,17 +33,10 @@
|
||||||
static pin_t tone_pin;
|
static pin_t tone_pin;
|
||||||
volatile static int32_t toggles;
|
volatile static int32_t toggles;
|
||||||
|
|
||||||
void toneInit() {
|
|
||||||
HAL_timer_start(TONE_TIMER_NUM, 100000);
|
|
||||||
HAL_timer_disable_interrupt(TONE_TIMER_NUM);
|
|
||||||
}
|
|
||||||
|
|
||||||
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
|
void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
|
||||||
tone_pin = _pin;
|
tone_pin = _pin;
|
||||||
toggles = 2 * frequency * duration / 1000;
|
toggles = 2 * frequency * duration / 1000;
|
||||||
HAL_timer_set_count(TONE_TIMER_NUM, 0); // ensure first beep is correct (make sure counter is less than the compare value)
|
HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
|
||||||
HAL_timer_set_compare(TONE_TIMER_NUM, VARIANT_MCK / 2 / 2 / frequency); // 84MHz / 2 prescaler / 2 interrupts per cycle /Hz
|
|
||||||
HAL_timer_enable_interrupt(TONE_TIMER_NUM);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void noTone(const pin_t _pin) {
|
void noTone(const pin_t _pin) {
|
||||||
|
@ -60,7 +53,6 @@ HAL_TONE_TIMER_ISR {
|
||||||
digitalWrite(tone_pin, (pin_state ^= 1));
|
digitalWrite(tone_pin, (pin_state ^= 1));
|
||||||
}
|
}
|
||||||
else noTone(tone_pin); // turn off interrupt
|
else noTone(tone_pin); // turn off interrupt
|
||||||
HAL_timer_restrain_count(TONE_TIMER_NUM, 10); // make sure next ISR isn't delayed by up to 2 minutes
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // ARDUINO_ARCH_SAM
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -642,5 +642,6 @@ U16 stream_stop(U8 id)
|
||||||
|
|
||||||
//! @}
|
//! @}
|
||||||
|
|
||||||
#endif // ACCESS_STREAM == true
|
#endif // ACCESS_STREAM
|
||||||
#endif
|
|
||||||
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -119,4 +119,4 @@ void sysclk_disable_usb(void)
|
||||||
/**INDENT-ON**/
|
/**INDENT-ON**/
|
||||||
/// @endcond
|
/// @endcond
|
||||||
|
|
||||||
#endif
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -1146,4 +1146,4 @@ bool udc_process_setup(void)
|
||||||
|
|
||||||
//! @}
|
//! @}
|
||||||
|
|
||||||
#endif
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -1152,4 +1152,4 @@ iram_size_t udi_cdc_write_buf(const void* buf, iram_size_t size)
|
||||||
|
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
#endif
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -255,5 +255,7 @@ UDC_DESC_STORAGE udc_config_t udc_config = {
|
||||||
|
|
||||||
//@}
|
//@}
|
||||||
//@}
|
//@}
|
||||||
#endif
|
|
||||||
#endif
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -187,5 +187,6 @@ UDC_DESC_STORAGE udc_config_t udc_config = {
|
||||||
/**INDENT-ON**/
|
/**INDENT-ON**/
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
#endif
|
#endif // ARDUINO_ARCH_SAM
|
||||||
#endif
|
|
||||||
|
#endif // SDSUPPORT
|
||||||
|
|
|
@ -1127,5 +1127,6 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size,
|
||||||
|
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
#endif
|
#endif // SDSUPPORT
|
||||||
#endif
|
|
||||||
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -2070,4 +2070,4 @@ static bool udd_ep_interrupt(void)
|
||||||
|
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
#endif
|
#endif // ARDUINO_ARCH_SAM
|
||||||
|
|
|
@ -238,5 +238,4 @@ void otg_dual_disable(void);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#endif /* UOTGHS_OTG_H_INCLUDED */
|
#endif /* UOTGHS_OTG_H_INCLUDED */
|
||||||
|
|
|
@ -56,7 +56,7 @@
|
||||||
static volatile bool main_b_cdc_enable = false;
|
static volatile bool main_b_cdc_enable = false;
|
||||||
static volatile bool main_b_dtr_active = false;
|
static volatile bool main_b_dtr_active = false;
|
||||||
|
|
||||||
void HAL_idletask(void) {
|
void usb_task_idle(void) {
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
// Attend SD card access from the USB MSD -- Prioritize access to improve speed
|
// Attend SD card access from the USB MSD -- Prioritize access to improve speed
|
||||||
int delay = 2;
|
int delay = 2;
|
||||||
|
@ -107,8 +107,15 @@ void usb_task_cdc_set_dtr(const uint8_t port, const bool b_enable) {
|
||||||
|
|
||||||
if (1200 == dwDTERate) {
|
if (1200 == dwDTERate) {
|
||||||
// We check DTR state to determine if host port is open (bit 0 of lineState).
|
// We check DTR state to determine if host port is open (bit 0 of lineState).
|
||||||
if (!b_enable)
|
if (!b_enable) {
|
||||||
|
|
||||||
|
// Set RST pin to go low for 65535 clock cycles on reset
|
||||||
|
// This helps restarting when firmware flash ends
|
||||||
|
RSTC->RSTC_MR = 0xA5000F01;
|
||||||
|
|
||||||
|
// Schedule delayed reset
|
||||||
initiateReset(250);
|
initiateReset(250);
|
||||||
|
}
|
||||||
else
|
else
|
||||||
cancelReset();
|
cancelReset();
|
||||||
}
|
}
|
||||||
|
@ -290,7 +297,7 @@ bool usb_task_other_requests(void) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void HAL_init(void) {
|
void usb_task_init(void) {
|
||||||
|
|
||||||
uint16_t *ptr;
|
uint16_t *ptr;
|
||||||
|
|
||||||
|
|
|
@ -49,6 +49,10 @@
|
||||||
|
|
||||||
#include "usb_protocol_cdc.h"
|
#include "usb_protocol_cdc.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
/*! \brief Called by MSC interface
|
/*! \brief Called by MSC interface
|
||||||
* Callback running when USB Host enable MSC interface
|
* Callback running when USB Host enable MSC interface
|
||||||
*
|
*
|
||||||
|
@ -111,8 +115,20 @@ void usb_task_cdc_rx_notify(const uint8_t port);
|
||||||
*/
|
*/
|
||||||
void usb_task_cdc_config(const uint8_t port, usb_cdc_line_coding_t *cfg);
|
void usb_task_cdc_config(const uint8_t port, usb_cdc_line_coding_t *cfg);
|
||||||
|
|
||||||
/* The USB device interrupt
|
/*! \brief The USB device interrupt
|
||||||
*/
|
*/
|
||||||
void USBD_ISR(void);
|
void USBD_ISR(void);
|
||||||
|
|
||||||
#endif // _MAIN_H_
|
/*! \brief USB task init
|
||||||
|
*/
|
||||||
|
void usb_task_init(void);
|
||||||
|
|
||||||
|
/*! \brief USB task idle
|
||||||
|
*/
|
||||||
|
void usb_task_idle(void);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // _USB_TASK_H_
|
||||||
|
|
|
@ -23,17 +23,88 @@
|
||||||
#ifdef ARDUINO_ARCH_SAM
|
#ifdef ARDUINO_ARCH_SAM
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
#include "../../Marlin.h"
|
||||||
|
#include "watchdog_Due.h"
|
||||||
|
|
||||||
|
// Override Arduino runtime to either config or disable the watchdog
|
||||||
|
//
|
||||||
|
// We need to configure the watchdog as soon as possible in the boot
|
||||||
|
// process, because watchdog initialization at hardware reset on SAM3X8E
|
||||||
|
// is unreliable, and there is risk of unintended resets if we delay
|
||||||
|
// that initialization to a later time.
|
||||||
|
void watchdogSetup(void) {
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
|
||||||
#include "watchdog_Due.h"
|
// 4 seconds timeout
|
||||||
|
uint32_t timeout = 4000;
|
||||||
|
|
||||||
void watchdogSetup(void) {
|
// Calculate timeout value in WDT counter ticks: This assumes
|
||||||
// do whatever. don't remove this function.
|
// the slow clock is running at 32.768 kHz watchdog
|
||||||
|
// frequency is therefore 32768 / 128 = 256 Hz
|
||||||
|
timeout = (timeout << 8) / 1000;
|
||||||
|
if (timeout == 0)
|
||||||
|
timeout = 1;
|
||||||
|
else if (timeout > 0xFFF)
|
||||||
|
timeout = 0xFFF;
|
||||||
|
|
||||||
|
// We want to enable the watchdog with the specified timeout
|
||||||
|
uint32_t value =
|
||||||
|
WDT_MR_WDV(timeout) | // With the specified timeout
|
||||||
|
WDT_MR_WDD(timeout) | // and no invalid write window
|
||||||
|
#if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
|
||||||
|
WDT_MR_WDRPROC | // WDT fault resets processor only - We want
|
||||||
|
// to keep PIO controller state
|
||||||
|
#endif
|
||||||
|
WDT_MR_WDDBGHLT | // WDT stops in debug state.
|
||||||
|
WDT_MR_WDIDLEHLT; // WDT stops in idle state.
|
||||||
|
|
||||||
|
#if ENABLED(WATCHDOG_RESET_MANUAL)
|
||||||
|
// We enable the watchdog timer, but only for the interrupt.
|
||||||
|
|
||||||
|
// Configure WDT to only trigger an interrupt
|
||||||
|
value |= WDT_MR_WDFIEN; // Enable WDT fault interrupt.
|
||||||
|
|
||||||
|
// Disable WDT interrupt (just in case, to avoid triggering it!)
|
||||||
|
NVIC_DisableIRQ(WDT_IRQn);
|
||||||
|
|
||||||
|
// Initialize WDT with the given parameters
|
||||||
|
WDT_Enable(WDT, value);
|
||||||
|
|
||||||
|
// 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
|
||||||
|
|
||||||
|
// a WDT fault triggers a reset
|
||||||
|
value |= WDT_MR_WDRSTEN;
|
||||||
|
|
||||||
|
// Initialize WDT with the given parameters
|
||||||
|
WDT_Enable(WDT, value);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Reset the watchdog
|
||||||
|
WDT_Restart(WDT);
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
// Make sure to completely disable the Watchdog
|
||||||
|
WDT_Disable(WDT);
|
||||||
|
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void watchdog_init(void) { watchdogEnable(4000); }
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
// Initialize watchdog - On SAM3X, Watchdog was already configured
|
||||||
|
// and enabled or disabled at startup, so no need to reconfigure it
|
||||||
|
// here.
|
||||||
|
void watchdog_init(void) {
|
||||||
|
// Reset watchdog to start clean
|
||||||
|
WDT_Restart(WDT);
|
||||||
|
}
|
||||||
#endif // USE_WATCHDOG
|
#endif // USE_WATCHDOG
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -648,9 +648,6 @@ void setup() {
|
||||||
|
|
||||||
#ifdef HAL_INIT
|
#ifdef HAL_INIT
|
||||||
HAL_init();
|
HAL_init();
|
||||||
#if defined(ARDUINO_ARCH_SAM) && PIN_EXISTS(BEEPER) && ENABLED(SPEAKER)
|
|
||||||
toneInit();
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(MAX7219_DEBUG)
|
#if ENABLED(MAX7219_DEBUG)
|
||||||
|
|
|
@ -1396,4 +1396,7 @@
|
||||||
#define HAS_FOLDER_SORTING (FOLDER_SORTING || ENABLED(SDSORT_GCODE))
|
#define HAS_FOLDER_SORTING (FOLDER_SORTING || ENABLED(SDSORT_GCODE))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// If platform requires early initialization of watchdog to properly boot
|
||||||
|
#define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM))
|
||||||
|
|
||||||
#endif // CONDITIONALS_POST_H
|
#endif // CONDITIONALS_POST_H
|
||||||
|
|
|
@ -117,6 +117,10 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 },
|
||||||
|
|
||||||
// private:
|
// private:
|
||||||
|
|
||||||
|
#if EARLY_WATCHDOG
|
||||||
|
bool Temperature::inited = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
|
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
|
||||||
uint16_t Temperature::redundant_temperature_raw = 0;
|
uint16_t Temperature::redundant_temperature_raw = 0;
|
||||||
float Temperature::redundant_temperature = 0.0;
|
float Temperature::redundant_temperature = 0.0;
|
||||||
|
@ -761,6 +765,14 @@ float Temperature::get_pid_output(const int8_t e) {
|
||||||
*/
|
*/
|
||||||
void Temperature::manage_heater() {
|
void Temperature::manage_heater() {
|
||||||
|
|
||||||
|
#if EARLY_WATCHDOG
|
||||||
|
// If thermal manager is still not running, make sure to at least reset the watchdog!
|
||||||
|
if (!inited) {
|
||||||
|
watchdog_reset();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(PROBING_HEATERS_OFF) && ENABLED(BED_LIMIT_SWITCHING)
|
#if ENABLED(PROBING_HEATERS_OFF) && ENABLED(BED_LIMIT_SWITCHING)
|
||||||
static bool last_pause_state;
|
static bool last_pause_state;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1053,6 +1065,12 @@ void Temperature::updateTemperaturesFromRawValues() {
|
||||||
*/
|
*/
|
||||||
void Temperature::init() {
|
void Temperature::init() {
|
||||||
|
|
||||||
|
#if EARLY_WATCHDOG
|
||||||
|
// Flag that the thermalManager should be running
|
||||||
|
if (inited) return;
|
||||||
|
inited = true;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if MB(RUMBA) && (TEMP_SENSOR_0 == -1 || TEMP_SENSOR_1 == -1 || TEMP_SENSOR_2 == -1 || TEMP_SENSOR_BED == -1)
|
#if MB(RUMBA) && (TEMP_SENSOR_0 == -1 || TEMP_SENSOR_1 == -1 || TEMP_SENSOR_2 == -1 || TEMP_SENSOR_BED == -1)
|
||||||
// Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
|
// Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
|
||||||
MCUCR = _BV(JTD);
|
MCUCR = _BV(JTD);
|
||||||
|
|
|
@ -202,6 +202,11 @@ class Temperature {
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
#if EARLY_WATCHDOG
|
||||||
|
// If temperature controller is running
|
||||||
|
static bool inited;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
|
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
|
||||||
static uint16_t redundant_temperature_raw;
|
static uint16_t redundant_temperature_raw;
|
||||||
static float redundant_temperature;
|
static float redundant_temperature;
|
||||||
|
|
|
@ -260,6 +260,11 @@ bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
|
||||||
// must supply min of 74 clock cycles with CS high.
|
// must supply min of 74 clock cycles with CS high.
|
||||||
for (uint8_t i = 0; i < 10; i++) spiSend(0xFF);
|
for (uint8_t i = 0; i < 10; i++) spiSend(0xFF);
|
||||||
|
|
||||||
|
// Initialization can cause the watchdog to timeout, so reinit it here
|
||||||
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
watchdog_reset();
|
||||||
|
#endif
|
||||||
|
|
||||||
// command to go idle in SPI mode
|
// command to go idle in SPI mode
|
||||||
while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
|
while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
|
||||||
if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
|
if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
|
||||||
|
@ -272,6 +277,11 @@ bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
|
||||||
crcSupported = (cardCommand(CMD59, 1) == R1_IDLE_STATE);
|
crcSupported = (cardCommand(CMD59, 1) == R1_IDLE_STATE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Initialization can cause the watchdog to timeout, so reinit it here
|
||||||
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
watchdog_reset();
|
||||||
|
#endif
|
||||||
|
|
||||||
// check SD version
|
// check SD version
|
||||||
for (;;) {
|
for (;;) {
|
||||||
if (cardCommand(CMD8, 0x1AA) == (R1_ILLEGAL_COMMAND | R1_IDLE_STATE)) {
|
if (cardCommand(CMD8, 0x1AA) == (R1_ILLEGAL_COMMAND | R1_IDLE_STATE)) {
|
||||||
|
@ -292,6 +302,11 @@ bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Initialization can cause the watchdog to timeout, so reinit it here
|
||||||
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
watchdog_reset();
|
||||||
|
#endif
|
||||||
|
|
||||||
// initialize card and send host supports SDHC if SD2
|
// initialize card and send host supports SDHC if SD2
|
||||||
arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0;
|
arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0;
|
||||||
while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
|
while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
|
||||||
|
|
Loading…
Reference in a new issue