mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_ChibiOS: cope with flash erase in expected delay
when there has been a flash erase when we are definately in an expected delay
This commit is contained in:
parent
445759295d
commit
0c440d5675
@ -35,6 +35,7 @@
|
|||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include "hwdef/common/stm32_util.h"
|
#include "hwdef/common/stm32_util.h"
|
||||||
|
#include "hwdef/common/flash.h"
|
||||||
#include "hwdef/common/watchdog.h"
|
#include "hwdef/common/watchdog.h"
|
||||||
#include <AP_Filesystem/AP_Filesystem.h>
|
#include <AP_Filesystem/AP_Filesystem.h>
|
||||||
#include "shared_dma.h"
|
#include "shared_dma.h"
|
||||||
@ -344,6 +345,11 @@ bool Scheduler::in_expected_delay(void) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#ifndef HAL_NO_FLASH_SUPPORT
|
||||||
|
if (stm32_flash_recent_erase()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -393,7 +399,7 @@ void Scheduler::_monitor_thread(void *arg)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
if (loop_delay >= 500) {
|
if (loop_delay >= 500 && !sched->in_expected_delay()) {
|
||||||
// at 500ms we declare an internal error
|
// at 500ms we declare an internal error
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
|
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
|
||||||
}
|
}
|
||||||
|
@ -52,6 +52,7 @@
|
|||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include "stm32_util.h"
|
#include "stm32_util.h"
|
||||||
|
#include "hrt.h"
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
|
|
||||||
@ -334,6 +335,8 @@ bool stm32_flash_ispageerased(uint32_t page)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static uint32_t last_erase_ms;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
erase a page
|
erase a page
|
||||||
*/
|
*/
|
||||||
@ -343,6 +346,8 @@ bool stm32_flash_erasepage(uint32_t page)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
last_erase_ms = hrt_millis32();
|
||||||
|
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
syssts_t sts = chSysGetStatusAndLockX();
|
syssts_t sts = chSysGetStatusAndLockX();
|
||||||
#endif
|
#endif
|
||||||
@ -401,6 +406,9 @@ bool stm32_flash_erasepage(uint32_t page)
|
|||||||
#if STM32_FLASH_DISABLE_ISR
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
chSysRestoreStatusX(sts);
|
chSysRestoreStatusX(sts);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
last_erase_ms = hrt_millis32();
|
||||||
|
|
||||||
return stm32_flash_ispageerased(page);
|
return stm32_flash_ispageerased(page);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -655,5 +663,13 @@ void stm32_flash_keep_unlocked(bool set)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if we had a recent erase
|
||||||
|
*/
|
||||||
|
bool stm32_flash_recent_erase(void)
|
||||||
|
{
|
||||||
|
return hrt_millis32() - last_erase_ms < 3000U;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // HAL_NO_FLASH_SUPPORT
|
#endif // HAL_NO_FLASH_SUPPORT
|
||||||
|
|
||||||
|
@ -27,6 +27,7 @@ bool stm32_flash_erasepage(uint32_t page);
|
|||||||
bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count);
|
bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count);
|
||||||
void stm32_flash_keep_unlocked(bool set);
|
void stm32_flash_keep_unlocked(bool set);
|
||||||
bool stm32_flash_ispageerased(uint32_t page);
|
bool stm32_flash_ispageerased(uint32_t page);
|
||||||
|
bool stm32_flash_recent_erase(void);
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user