mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Periph: add debug option for hold in bootloader after 15s
This commit is contained in:
parent
e94f28c81d
commit
068208e4d7
@ -384,12 +384,21 @@ void AP_Periph_FW::update()
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||
static uint32_t last_debug_ms;
|
||||
if (g.debug==1 && now - last_debug_ms > 5000) {
|
||||
if ((g.debug&(1<<DEBUG_SHOW_STACK)) && now - last_debug_ms > 5000) {
|
||||
last_debug_ms = now;
|
||||
show_stack_free();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
if ((g.debug&(1<<DEBUG_AUTOREBOOT)) && AP_HAL::millis() > 15000) {
|
||||
// attempt reboot with HOLD after 15s
|
||||
periph.prepare_reboot();
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_HOLD));
|
||||
NVIC_SystemReset();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_BATTERY
|
||||
if (now - battery.last_read_ms >= 100) {
|
||||
// update battery at 10Hz
|
||||
|
@ -247,6 +247,11 @@ public:
|
||||
|
||||
static AP_Periph_FW *_singleton;
|
||||
|
||||
enum {
|
||||
DEBUG_SHOW_STACK,
|
||||
DEBUG_AUTOREBOOT
|
||||
};
|
||||
|
||||
// show stack as DEBUG msgs
|
||||
void show_stack_free();
|
||||
|
||||
|
@ -136,10 +136,11 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
||||
// @Param: DEBUG
|
||||
// @DisplayName: Debug
|
||||
// @Description: Debug
|
||||
// @Values: 0:Disabled, 1:Show free stack space
|
||||
// @Bitmask: 0:Disabled, 1:Show free stack space, 2:Auto Reboot after 15sec
|
||||
// @User: Advanced
|
||||
GSCALAR(debug, "DEBUG", 0),
|
||||
|
||||
|
||||
// @Param: BRD_SERIAL_NUM
|
||||
// @DisplayName: Serial number of device
|
||||
// @Description: Non-zero positive values will be shown on the CAN App Name string
|
||||
|
Loading…
Reference in New Issue
Block a user