mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: added IWDG watchdog support
this resets the MCU if the main loop stops for 1 second # Conflicts: # libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
This commit is contained in:
parent
234b3391a9
commit
a7906f9e42
@ -26,6 +26,7 @@
|
||||
#include "sdcard.h"
|
||||
#include "hwdef/common/usbcfg.h"
|
||||
#include "hwdef/common/stm32_util.h"
|
||||
#include "hwdef/common/watchdog.h"
|
||||
|
||||
#include <hwdef.h>
|
||||
|
||||
@ -187,6 +188,9 @@ static THD_FUNCTION(main_loop,arg)
|
||||
*/
|
||||
chThdSetPriority(APM_MAIN_PRIORITY);
|
||||
|
||||
// setup watchdog to reset if main loop stops
|
||||
stm32_watchdog_init();
|
||||
|
||||
while (true) {
|
||||
g_callbacks->loop();
|
||||
|
||||
@ -201,6 +205,7 @@ static THD_FUNCTION(main_loop,arg)
|
||||
if (!schedulerInstance.check_called_boost()) {
|
||||
hal.scheduler->delay_microseconds(250);
|
||||
}
|
||||
stm32_watchdog_pat();
|
||||
}
|
||||
thread_running = false;
|
||||
}
|
||||
|
@ -129,8 +129,9 @@ CSRC = $(STARTUPSRC) \
|
||||
$(HWDEF)/common/malloc.c \
|
||||
$(HWDEF)/common/stdio.c \
|
||||
$(HWDEF)/common/hrt.c \
|
||||
$(HWDEF)/common/stm32_util.c \
|
||||
$(HWDEF)/common/bouncebuffer.c
|
||||
$(HWDEF)/common/stm32_util.c \
|
||||
$(HWDEF)/common/bouncebuffer.c \
|
||||
$(HWDEF)/common/watchdog.c
|
||||
|
||||
ifeq ($(USE_FATFS),yes)
|
||||
CSRC += $(HWDEF)/common/posix.c
|
||||
|
48
libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c
Normal file
48
libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c
Normal file
@ -0,0 +1,48 @@
|
||||
/*
|
||||
independent watchdog support
|
||||
*/
|
||||
|
||||
#include "hal.h"
|
||||
#include "watchdog.h"
|
||||
|
||||
#ifndef IWDG_BASE
|
||||
#if defined(STM32H7)
|
||||
#define IWDG_BASE 0x58004800
|
||||
#elif defined(STM32F7) || defined(STM32F4) || defined(STM32F1)
|
||||
#define IWDG_BASE 0x40003000
|
||||
#else
|
||||
#error "Unknown IWDG_BASE"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
typedef struct
|
||||
{
|
||||
__IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */
|
||||
__IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */
|
||||
__IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */
|
||||
__IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */
|
||||
__IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */
|
||||
} IWDG_Regs;
|
||||
|
||||
#define IWDGD (*(IWDG_Regs *)(IWDG_BASE))
|
||||
|
||||
/*
|
||||
setup the watchdog
|
||||
*/
|
||||
void stm32_watchdog_init(void)
|
||||
{
|
||||
// setup for 1s reset
|
||||
IWDGD.KR = 0x5555;
|
||||
IWDGD.PR = 8;
|
||||
IWDGD.RLR = 0xFFF;
|
||||
IWDGD.KR = 0xCCCC;
|
||||
}
|
||||
|
||||
/*
|
||||
pat the dog, to prevent a reset. If not called for 1s
|
||||
after stm32_watchdog_init() then MCU will reset
|
||||
*/
|
||||
void stm32_watchdog_pat(void)
|
||||
{
|
||||
IWDGD.KR = 0xAAAA;
|
||||
}
|
20
libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h
Normal file
20
libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h
Normal file
@ -0,0 +1,20 @@
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/*
|
||||
setup the watchdog
|
||||
*/
|
||||
void stm32_watchdog_init(void);
|
||||
|
||||
/*
|
||||
pat the dog, to prevent a reset. If not called for 1s
|
||||
after stm32_watchdog_init() then MCU will reset
|
||||
*/
|
||||
void stm32_watchdog_pat(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user