mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: move crashcatcher methods out from system.cpp into hwdef common
This commit is contained in:
parent
06725ed68a
commit
bd08d2d257
@ -130,7 +130,8 @@ CSRC += $(HWDEF)/common/stubs.c \
|
||||
# test.c
|
||||
|
||||
LIBCC_CSRC = $(CRASHCATCHER)/Core/src/CrashCatcher.c \
|
||||
$(CRASHCATCHER)/HexDump/src/HexDump.c
|
||||
$(CRASHCATCHER)/HexDump/src/HexDump.c \
|
||||
$(HWDEF)/common/crashcatcher.c
|
||||
|
||||
LIBCC_ASMXSRC = $(CRASHCATCHER)/Core/src/CrashCatcher_armv7m.S
|
||||
|
||||
|
@ -123,77 +123,6 @@ void MemManage_Handler(void);
|
||||
void MemManage_Handler(void) {
|
||||
HardFault_Handler();
|
||||
}
|
||||
|
||||
/*
|
||||
initialise serial ports
|
||||
*/
|
||||
static void init_uarts(void)
|
||||
{
|
||||
USART_TypeDef *u = HAL_CRASH_SERIAL_PORT;
|
||||
IRQ_DISABLE_HAL_CRASH_SERIAL_PORT();
|
||||
RCC_RESET_HAL_CRASH_SERIAL_PORT();
|
||||
uint32_t fck = (uint32_t)(((HAL_CRASH_SERIAL_PORT_CLOCK + ((HAL_CRASH_SERIAL_PORT_BAUD)/2)) / HAL_CRASH_SERIAL_PORT_BAUD));
|
||||
|
||||
u->BRR = fck;
|
||||
|
||||
/* Resetting eventual pending status flags.*/
|
||||
u->ICR = 0xFFFFFFFFU;
|
||||
|
||||
u->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
|
||||
|
||||
initialised = true;
|
||||
}
|
||||
|
||||
int CrashCatcher_getc(void);
|
||||
int CrashCatcher_getc(void)
|
||||
{
|
||||
if (!initialised) {
|
||||
init_uarts();
|
||||
}
|
||||
USART_TypeDef *u = HAL_CRASH_SERIAL_PORT;
|
||||
// wait for a follwing string, only then do we start dumping
|
||||
static const char* wait_for_string = "dump_crash_log";
|
||||
uint8_t curr_off = 0;
|
||||
while (true) {
|
||||
while (!(USART_ISR_RXNE & u->ISR)) {}
|
||||
uint8_t c = u->RDR;
|
||||
if (c == wait_for_string[curr_off]) {
|
||||
curr_off++;
|
||||
if (curr_off == strlen(wait_for_string)) {
|
||||
return 0;
|
||||
}
|
||||
} else {
|
||||
curr_off = 0;
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
void CrashCatcher_putc(int c);
|
||||
void CrashCatcher_putc(int c)
|
||||
{
|
||||
if (!initialised) {
|
||||
init_uarts();
|
||||
}
|
||||
USART_TypeDef *u = HAL_CRASH_SERIAL_PORT;
|
||||
u->TDR = c & 0xFF;
|
||||
while (!(USART_ISR_TC & u->ISR)) {
|
||||
// keep alive while dump is happening
|
||||
stm32_watchdog_pat();
|
||||
}
|
||||
}
|
||||
|
||||
extern uint32_t __ram0_start__, __ram0_end__;
|
||||
const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void);
|
||||
const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void)
|
||||
{
|
||||
static const CrashCatcherMemoryRegion regions[] = {
|
||||
{(uint32_t)&__ram0_start__, (uint32_t)&__ram0_end__, CRASH_CATCHER_BYTE},
|
||||
{0xFFFFFFFF, 0xFFFFFFFF, CRASH_CATCHER_BYTE}
|
||||
};
|
||||
return regions;
|
||||
}
|
||||
|
||||
}
|
||||
namespace AP_HAL {
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user