mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: resync for 4.0 update
This commit is contained in:
parent
e6c8b61b38
commit
7de195e3f6
|
@ -12,7 +12,6 @@ class ADCSource;
|
|||
class RCInput;
|
||||
class Util;
|
||||
class Semaphore;
|
||||
class Semaphore_Recursive;
|
||||
class GPIO;
|
||||
class DigitalSource;
|
||||
class HALSITLCAN;
|
||||
|
|
|
@ -162,9 +162,10 @@ 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;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -185,11 +186,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);
|
||||
|
|
|
@ -17,6 +17,13 @@ using namespace HALSITL;
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifndef SITL_STACK_CHECKING_ENABLED
|
||||
//#define SITL_STACK_CHECKING_ENABLED !defined(__CYGWIN__) && !defined(__CYGWIN64__)
|
||||
// stack checking is disabled until the memory corruption issues are
|
||||
// fixed with pthread_attr_setstack. These may be due to
|
||||
// changes in the way guard pages are handled.
|
||||
#define SITL_STACK_CHECKING_ENABLED 0
|
||||
#endif
|
||||
|
||||
AP_HAL::Proc Scheduler::_failsafe = nullptr;
|
||||
|
||||
|
@ -233,7 +240,9 @@ void Scheduler::_run_io_procs()
|
|||
hal.uartH->_timer_tick();
|
||||
hal.storage->_timer_tick();
|
||||
|
||||
#if SITL_STACK_CHECKING_ENABLED
|
||||
check_thread_stacks();
|
||||
#endif
|
||||
|
||||
AP::RC().update();
|
||||
}
|
||||
|
@ -315,8 +324,10 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
|||
a->f[0] = proc;
|
||||
a->name = name;
|
||||
|
||||
pthread_attr_init(&a->attr);
|
||||
#if !defined(__CYGWIN__) && !defined(__CYGWIN64__)
|
||||
if (pthread_attr_init(&a->attr) != 0) {
|
||||
goto failed;
|
||||
}
|
||||
#if SITL_STACK_CHECKING_ENABLED
|
||||
if (pthread_attr_setstack(&a->attr, a->stack, alloc_stack) != 0) {
|
||||
AP_HAL::panic("Failed to set stack of size %u for thread %s", alloc_stack, name);
|
||||
}
|
||||
|
|
|
@ -11,12 +11,6 @@ using namespace HALSITL;
|
|||
|
||||
// construct a semaphore
|
||||
Semaphore::Semaphore()
|
||||
{
|
||||
pthread_mutex_init(&_lock, nullptr);
|
||||
}
|
||||
|
||||
// construct a recursive semaphore (allows a thread to take it more than once)
|
||||
Semaphore_Recursive::Semaphore_Recursive()
|
||||
{
|
||||
pthread_mutexattr_t attr;
|
||||
pthread_mutexattr_init(&attr);
|
||||
|
|
|
@ -16,11 +16,3 @@ public:
|
|||
protected:
|
||||
pthread_mutex_t _lock;
|
||||
};
|
||||
|
||||
|
||||
class HALSITL::Semaphore_Recursive : public HALSITL::Semaphore {
|
||||
public:
|
||||
Semaphore_Recursive();
|
||||
};
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue