mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Global: remove {begin,end}_atomic from scheduler
These are never used and largely not implemented.
This commit is contained in:
parent
9aa49cda93
commit
2b61eaf9f2
@ -42,12 +42,6 @@ bool Scheduler::in_timerprocess() {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::begin_atomic()
|
|
||||||
{}
|
|
||||||
|
|
||||||
void Scheduler::end_atomic()
|
|
||||||
{}
|
|
||||||
|
|
||||||
void Scheduler::system_initialized()
|
void Scheduler::system_initialized()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
@ -22,9 +22,6 @@ public:
|
|||||||
|
|
||||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||||
|
|
||||||
void begin_atomic();
|
|
||||||
void end_atomic();
|
|
||||||
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
@ -165,16 +165,6 @@ void FLYMAPLEScheduler::_failsafe_timer_event()
|
|||||||
_failsafe();
|
_failsafe();
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLEScheduler::begin_atomic()
|
|
||||||
{
|
|
||||||
noInterrupts();
|
|
||||||
}
|
|
||||||
|
|
||||||
void FLYMAPLEScheduler::end_atomic()
|
|
||||||
{
|
|
||||||
interrupts();
|
|
||||||
}
|
|
||||||
|
|
||||||
void FLYMAPLEScheduler::_run_timer_procs(bool called_from_isr)
|
void FLYMAPLEScheduler::_run_timer_procs(bool called_from_isr)
|
||||||
{
|
{
|
||||||
_in_timer_proc = true;
|
_in_timer_proc = true;
|
||||||
|
@ -43,9 +43,6 @@ public:
|
|||||||
|
|
||||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||||
|
|
||||||
void begin_atomic();
|
|
||||||
void end_atomic();
|
|
||||||
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
@ -397,12 +397,6 @@ bool Scheduler::in_timerprocess()
|
|||||||
return _in_timer_proc;
|
return _in_timer_proc;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::begin_atomic()
|
|
||||||
{}
|
|
||||||
|
|
||||||
void Scheduler::end_atomic()
|
|
||||||
{}
|
|
||||||
|
|
||||||
void Scheduler::_wait_all_threads()
|
void Scheduler::_wait_all_threads()
|
||||||
{
|
{
|
||||||
int r = pthread_barrier_wait(&_initialized_barrier);
|
int r = pthread_barrier_wait(&_initialized_barrier);
|
||||||
|
@ -34,9 +34,6 @@ public:
|
|||||||
|
|
||||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||||
|
|
||||||
void begin_atomic();
|
|
||||||
void end_atomic();
|
|
||||||
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
Loading…
Reference in New Issue
Block a user