mirror of https://github.com/ArduPilot/ardupilot
Global: remove system_initializing() from scheduler
This is not used anymore.
This commit is contained in:
parent
9cf9fc152b
commit
9aa49cda93
|
@ -54,7 +54,6 @@ public:
|
||||||
virtual void register_timer_failsafe(AP_HAL::Proc,
|
virtual void register_timer_failsafe(AP_HAL::Proc,
|
||||||
uint32_t period_us) = 0;
|
uint32_t period_us) = 0;
|
||||||
|
|
||||||
virtual bool system_initializing() = 0;
|
|
||||||
virtual void system_initialized() = 0;
|
virtual void system_initialized() = 0;
|
||||||
|
|
||||||
virtual void reboot(bool hold_in_bootloader) = 0;
|
virtual void reboot(bool hold_in_bootloader) = 0;
|
||||||
|
|
|
@ -48,10 +48,6 @@ void Scheduler::begin_atomic()
|
||||||
void Scheduler::end_atomic()
|
void Scheduler::end_atomic()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
bool Scheduler::system_initializing() {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::system_initialized()
|
void Scheduler::system_initialized()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,6 @@ public:
|
||||||
void begin_atomic();
|
void begin_atomic();
|
||||||
void end_atomic();
|
void end_atomic();
|
||||||
|
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
|
@ -193,10 +193,6 @@ void FLYMAPLEScheduler::_run_timer_procs(bool called_from_isr)
|
||||||
_in_timer_proc = false;
|
_in_timer_proc = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool FLYMAPLEScheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void FLYMAPLEScheduler::system_initialized()
|
void FLYMAPLEScheduler::system_initialized()
|
||||||
{
|
{
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
|
|
|
@ -46,7 +46,6 @@ public:
|
||||||
void begin_atomic();
|
void begin_atomic();
|
||||||
void end_atomic();
|
void end_atomic();
|
||||||
|
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
|
@ -403,10 +403,6 @@ void Scheduler::begin_atomic()
|
||||||
void Scheduler::end_atomic()
|
void Scheduler::end_atomic()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
bool Scheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::_wait_all_threads()
|
void Scheduler::_wait_all_threads()
|
||||||
{
|
{
|
||||||
int r = pthread_barrier_wait(&_initialized_barrier);
|
int r = pthread_barrier_wait(&_initialized_barrier);
|
||||||
|
|
|
@ -37,7 +37,6 @@ public:
|
||||||
void begin_atomic();
|
void begin_atomic();
|
||||||
void end_atomic();
|
void end_atomic();
|
||||||
|
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
|
@ -367,10 +367,6 @@ bool PX4Scheduler::in_timerprocess()
|
||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool PX4Scheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PX4Scheduler::system_initialized() {
|
void PX4Scheduler::system_initialized() {
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
||||||
|
|
|
@ -58,7 +58,6 @@ public:
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
void hal_initialized() { _hal_initialized = true; }
|
void hal_initialized() { _hal_initialized = true; }
|
||||||
|
|
||||||
|
|
|
@ -272,10 +272,6 @@ bool Scheduler::in_timerprocess()
|
||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Scheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::system_initialized() {
|
void Scheduler::system_initialized() {
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
||||||
|
|
|
@ -32,7 +32,6 @@ public:
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
void hal_initialized();
|
void hal_initialized();
|
||||||
|
|
||||||
|
|
|
@ -122,10 +122,6 @@ bool Scheduler::in_timerprocess() {
|
||||||
return _in_timer_proc || _in_io_proc;
|
return _in_timer_proc || _in_io_proc;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Scheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::system_initialized() {
|
void Scheduler::system_initialized() {
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
AP_HAL::panic(
|
AP_HAL::panic(
|
||||||
|
|
|
@ -31,7 +31,6 @@ public:
|
||||||
|
|
||||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||||
|
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
|
@ -310,10 +310,6 @@ bool VRBRAINScheduler::in_timerprocess()
|
||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool VRBRAINScheduler::system_initializing() {
|
|
||||||
return !_initialized;
|
|
||||||
}
|
|
||||||
|
|
||||||
void VRBRAINScheduler::system_initialized() {
|
void VRBRAINScheduler::system_initialized() {
|
||||||
if (_initialized) {
|
if (_initialized) {
|
||||||
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
||||||
|
|
|
@ -37,7 +37,6 @@ public:
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
void hal_initialized() { _hal_initialized = true; }
|
void hal_initialized() { _hal_initialized = true; }
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue