mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
HAL_Linux: use a semaphore in suspend_timer_procs()
this is the start of multi-core aware code
This commit is contained in:
parent
dcdb53584b
commit
024d3b71e7
@ -198,19 +198,14 @@ void LinuxScheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t per
|
||||
|
||||
void LinuxScheduler::suspend_timer_procs()
|
||||
{
|
||||
_timer_suspended = true;
|
||||
while (_in_timer_proc) {
|
||||
delay_microseconds(20);
|
||||
if (!_timer_semaphore.take(0)) {
|
||||
printf("Failed to take timer semaphore\n");
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxScheduler::resume_timer_procs()
|
||||
{
|
||||
_timer_suspended = false;
|
||||
if (_timer_event_missed == true) {
|
||||
_run_timers(false);
|
||||
_timer_event_missed = false;
|
||||
}
|
||||
_timer_semaphore.give();
|
||||
}
|
||||
|
||||
void LinuxScheduler::_run_timers(bool called_from_timer_thread)
|
||||
@ -220,16 +215,16 @@ void LinuxScheduler::_run_timers(bool called_from_timer_thread)
|
||||
}
|
||||
_in_timer_proc = true;
|
||||
|
||||
if (!_timer_suspended) {
|
||||
// now call the timer based drivers
|
||||
for (int i = 0; i < _num_timer_procs; i++) {
|
||||
if (_timer_proc[i] != NULL) {
|
||||
_timer_proc[i]();
|
||||
}
|
||||
}
|
||||
} else if (called_from_timer_thread) {
|
||||
_timer_event_missed = true;
|
||||
if (!_timer_semaphore.take(0)) {
|
||||
printf("Failed to take timer semaphore in _run_timers\n");
|
||||
}
|
||||
// now call the timer based drivers
|
||||
for (int i = 0; i < _num_timer_procs; i++) {
|
||||
if (_timer_proc[i] != NULL) {
|
||||
_timer_proc[i]();
|
||||
}
|
||||
}
|
||||
_timer_semaphore.give();
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
@ -272,12 +267,10 @@ void LinuxScheduler::_run_io(void)
|
||||
}
|
||||
_in_io_proc = true;
|
||||
|
||||
if (!_timer_suspended) {
|
||||
// now call the IO based drivers
|
||||
for (int i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] != NULL) {
|
||||
_io_proc[i]();
|
||||
}
|
||||
// now call the IO based drivers
|
||||
for (int i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] != NULL) {
|
||||
_io_proc[i]();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -3,6 +3,7 @@
|
||||
#define __AP_HAL_LINUX_SCHEDULER_H__
|
||||
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include "Semaphores.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#include <sys/time.h>
|
||||
@ -56,8 +57,6 @@ private:
|
||||
bool _initialized;
|
||||
volatile bool _timer_pending;
|
||||
|
||||
volatile bool _timer_suspended;
|
||||
|
||||
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS];
|
||||
uint8_t _num_timer_procs;
|
||||
volatile bool _in_timer_proc;
|
||||
@ -83,6 +82,8 @@ private:
|
||||
void _setup_realtime(uint32_t size);
|
||||
|
||||
uint64_t stopped_clock_usec;
|
||||
|
||||
LinuxSemaphore _timer_semaphore;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
Loading…
Reference in New Issue
Block a user