mirror of https://github.com/ArduPilot/ardupilot
global: remove AP_HAL::in_timerprocess()
This is not used and in the only places it would make sense would be internally to the scheduler so remove it.
This commit is contained in:
parent
08637f1dcc
commit
5ea1784838
|
@ -42,8 +42,6 @@ public:
|
|||
virtual void suspend_timer_procs() = 0;
|
||||
virtual void resume_timer_procs() = 0;
|
||||
|
||||
virtual bool in_timerprocess() = 0;
|
||||
|
||||
virtual void register_timer_failsafe(AP_HAL::Proc,
|
||||
uint32_t period_us) = 0;
|
||||
|
||||
|
|
|
@ -38,10 +38,6 @@ void Scheduler::suspend_timer_procs()
|
|||
void Scheduler::resume_timer_procs()
|
||||
{}
|
||||
|
||||
bool Scheduler::in_timerprocess() {
|
||||
return false;
|
||||
}
|
||||
|
||||
void Scheduler::system_initialized()
|
||||
{}
|
||||
|
||||
|
|
|
@ -16,8 +16,6 @@ public:
|
|||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
|
||||
bool in_timerprocess();
|
||||
|
||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||
|
||||
void system_initialized();
|
||||
|
|
|
@ -348,11 +348,6 @@ void Scheduler::_io_task()
|
|||
_run_io();
|
||||
}
|
||||
|
||||
bool Scheduler::in_timerprocess()
|
||||
{
|
||||
return _in_timer_proc;
|
||||
}
|
||||
|
||||
bool Scheduler::in_main_thread()
|
||||
{
|
||||
return pthread_equal(pthread_self(), _main_ctx);
|
||||
|
|
|
@ -35,7 +35,6 @@ public:
|
|||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
|
||||
bool in_timerprocess();
|
||||
bool in_main_thread();
|
||||
|
||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||
|
|
|
@ -443,11 +443,6 @@ void *PX4Scheduler::_uavcan_thread(void *arg)
|
|||
}
|
||||
#endif
|
||||
|
||||
bool PX4Scheduler::in_timerprocess()
|
||||
{
|
||||
return getpid() != _main_task_pid;
|
||||
}
|
||||
|
||||
bool PX4Scheduler::in_main_thread()
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
|
|
|
@ -58,7 +58,6 @@ public:
|
|||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
bool in_timerprocess();
|
||||
bool in_main_thread();
|
||||
void system_initialized();
|
||||
void hal_initialized() { _hal_initialized = true; }
|
||||
|
|
|
@ -261,11 +261,6 @@ void *Scheduler::_io_thread(void *arg)
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
bool Scheduler::in_timerprocess()
|
||||
{
|
||||
return getpid() != _main_task_pid;
|
||||
}
|
||||
|
||||
bool Scheduler::in_main_thread()
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
|
|
|
@ -32,7 +32,6 @@ public:
|
|||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
bool in_main_thread();
|
||||
bool in_timerprocess();
|
||||
void system_initialized();
|
||||
void hal_initialized();
|
||||
|
||||
|
|
|
@ -111,10 +111,6 @@ void Scheduler::resume_timer_procs() {
|
|||
}
|
||||
}
|
||||
|
||||
bool Scheduler::in_timerprocess() {
|
||||
return _in_timer_proc || _in_io_proc;
|
||||
}
|
||||
|
||||
void Scheduler::system_initialized() {
|
||||
if (_initialized) {
|
||||
AP_HAL::panic(
|
||||
|
|
|
@ -27,8 +27,6 @@ public:
|
|||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
|
||||
bool in_timerprocess();
|
||||
|
||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||
|
||||
void system_initialized();
|
||||
|
|
|
@ -370,11 +370,6 @@ void *VRBRAINScheduler::_storage_thread(void *arg)
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
bool VRBRAINScheduler::in_timerprocess()
|
||||
{
|
||||
return getpid() != _main_task_pid;
|
||||
}
|
||||
|
||||
bool VRBRAINScheduler::in_main_thread()
|
||||
{
|
||||
return getpid() == _main_task_pid;
|
||||
|
|
|
@ -55,7 +55,6 @@ public:
|
|||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
bool in_timerprocess();
|
||||
void system_initialized();
|
||||
void hal_initialized() { _hal_initialized = true; }
|
||||
|
||||
|
|
Loading…
Reference in New Issue