mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed SemLine data in WDOG msg
semline was being overwritten in the setup() call
This commit is contained in:
parent
da3602b90d
commit
2d5e4dcfa2
|
@ -159,6 +159,8 @@ thread_t* get_main_thread()
|
||||||
|
|
||||||
static AP_HAL::HAL::Callbacks* g_callbacks;
|
static AP_HAL::HAL::Callbacks* g_callbacks;
|
||||||
|
|
||||||
|
static AP_HAL::Util::PersistentData last_persistent_data;
|
||||||
|
|
||||||
static void main_loop()
|
static void main_loop()
|
||||||
{
|
{
|
||||||
daemon_task = chThdGetSelfX();
|
daemon_task = chThdGetSelfX();
|
||||||
|
@ -200,6 +202,7 @@ static void main_loop()
|
||||||
if (stm32_was_watchdog_reset()) {
|
if (stm32_was_watchdog_reset()) {
|
||||||
// load saved watchdog data
|
// load saved watchdog data
|
||||||
stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4);
|
stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4);
|
||||||
|
last_persistent_data = utilInstance.persistent_data;
|
||||||
}
|
}
|
||||||
|
|
||||||
schedulerInstance.hal_initialized();
|
schedulerInstance.hal_initialized();
|
||||||
|
@ -216,7 +219,7 @@ static void main_loop()
|
||||||
|
|
||||||
if (hal.util->was_watchdog_reset()) {
|
if (hal.util->was_watchdog_reset()) {
|
||||||
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
|
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
|
||||||
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
const AP_HAL::Util::PersistentData &pd = last_persistent_data;
|
||||||
AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QbIIHHH",
|
AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QbIIHHH",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
pd.scheduler_task,
|
pd.scheduler_task,
|
||||||
|
|
Loading…
Reference in New Issue