HAL_Linux: resync for 4.0 update

This commit is contained in:
Andrew Tridgell 2020-05-11 15:55:35 +10:00
parent 31f7b32fab
commit b925cb121d
4 changed files with 7 additions and 16 deletions

View File

@ -237,9 +237,7 @@ void Scheduler::_timer_task()
void Scheduler::_run_io(void)
{
if (!_io_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return;
}
_io_semaphore.take_blocking();
// now call the IO based drivers
for (int i = 0; i < _num_io_procs; i++) {

View File

@ -8,12 +8,6 @@ using namespace Linux;
// 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);

View File

@ -18,9 +18,4 @@ protected:
pthread_mutex_t _lock;
};
class Semaphore_Recursive : public Semaphore {
public:
Semaphore_Recursive();
};
}

View File

@ -30,8 +30,12 @@ void panic(const char *errormsg, ...)
va_end(ap);
UNUSED_RESULT(write(1, "\n", 1));
hal.rcin->teardown();
hal.scheduler->delay_microseconds(10000);
if (hal.rcin != nullptr) {
hal.rcin->teardown();
}
if (hal.scheduler != nullptr) {
hal.scheduler->delay_microseconds(10000);
}
exit(1);
}