mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
HAL_Linux: resync for 4.0 update
This commit is contained in:
parent
31f7b32fab
commit
b925cb121d
@ -237,9 +237,7 @@ void Scheduler::_timer_task()
|
|||||||
|
|
||||||
void Scheduler::_run_io(void)
|
void Scheduler::_run_io(void)
|
||||||
{
|
{
|
||||||
if (!_io_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
_io_semaphore.take_blocking();
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// now call the IO based drivers
|
// now call the IO based drivers
|
||||||
for (int i = 0; i < _num_io_procs; i++) {
|
for (int i = 0; i < _num_io_procs; i++) {
|
||||||
|
@ -8,12 +8,6 @@ using namespace Linux;
|
|||||||
|
|
||||||
// construct a semaphore
|
// construct a semaphore
|
||||||
Semaphore::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_t attr;
|
||||||
pthread_mutexattr_init(&attr);
|
pthread_mutexattr_init(&attr);
|
||||||
|
@ -18,9 +18,4 @@ protected:
|
|||||||
pthread_mutex_t _lock;
|
pthread_mutex_t _lock;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Semaphore_Recursive : public Semaphore {
|
|
||||||
public:
|
|
||||||
Semaphore_Recursive();
|
|
||||||
};
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -30,8 +30,12 @@ void panic(const char *errormsg, ...)
|
|||||||
va_end(ap);
|
va_end(ap);
|
||||||
UNUSED_RESULT(write(1, "\n", 1));
|
UNUSED_RESULT(write(1, "\n", 1));
|
||||||
|
|
||||||
|
if (hal.rcin != nullptr) {
|
||||||
hal.rcin->teardown();
|
hal.rcin->teardown();
|
||||||
|
}
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
hal.scheduler->delay_microseconds(10000);
|
hal.scheduler->delay_microseconds(10000);
|
||||||
|
}
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user