diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index ac13ccdded..26ddf588c6 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -166,7 +166,7 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const analogin->init(); if (getenv("SITL_WATCHDOG_RESET")) { - AP::internalerror().error(AP_InternalError::error_t::watchdog_reset); + INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset); if (watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4)) { uartA->printf("Loaded watchdog data"); utilInstance.last_persistent_data = utilInstance.persistent_data; @@ -190,11 +190,12 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const if (getenv("SITL_WATCHDOG_RESET")) { const AP_HAL::Util::PersistentData &pd = util->persistent_data; - AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QbIIHHH", + AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine", "QbIHHHHH", AP_HAL::micros64(), pd.scheduler_task, pd.internal_errors, pd.internal_error_count, + pd.internal_error_last_line, pd.last_mavlink_msgid, pd.last_mavlink_cmd, pd.semaphore_line);