Browse Source

Global: remove system_initializing() from scheduler

This is not used anymore.
master
Lucas De Marchi 9 years ago
parent
commit
9aa49cda93
  1. 1
      libraries/AP_HAL/Scheduler.h
  2. 4
      libraries/AP_HAL_Empty/Scheduler.cpp
  3. 1
      libraries/AP_HAL_Empty/Scheduler.h
  4. 4
      libraries/AP_HAL_FLYMAPLE/Scheduler.cpp
  5. 1
      libraries/AP_HAL_FLYMAPLE/Scheduler.h
  6. 4
      libraries/AP_HAL_Linux/Scheduler.cpp
  7. 1
      libraries/AP_HAL_Linux/Scheduler.h
  8. 4
      libraries/AP_HAL_PX4/Scheduler.cpp
  9. 1
      libraries/AP_HAL_PX4/Scheduler.h
  10. 4
      libraries/AP_HAL_QURT/Scheduler.cpp
  11. 1
      libraries/AP_HAL_QURT/Scheduler.h
  12. 4
      libraries/AP_HAL_SITL/Scheduler.cpp
  13. 1
      libraries/AP_HAL_SITL/Scheduler.h
  14. 4
      libraries/AP_HAL_VRBRAIN/Scheduler.cpp
  15. 1
      libraries/AP_HAL_VRBRAIN/Scheduler.h

1
libraries/AP_HAL/Scheduler.h

@ -54,7 +54,6 @@ public: @@ -54,7 +54,6 @@ public:
virtual void register_timer_failsafe(AP_HAL::Proc,
uint32_t period_us) = 0;
virtual bool system_initializing() = 0;
virtual void system_initialized() = 0;
virtual void reboot(bool hold_in_bootloader) = 0;

4
libraries/AP_HAL_Empty/Scheduler.cpp

@ -48,10 +48,6 @@ void Scheduler::begin_atomic() @@ -48,10 +48,6 @@ void Scheduler::begin_atomic()
void Scheduler::end_atomic()
{}
bool Scheduler::system_initializing() {
return false;
}
void Scheduler::system_initialized()
{}

1
libraries/AP_HAL_Empty/Scheduler.h

@ -25,7 +25,6 @@ public: @@ -25,7 +25,6 @@ public:
void begin_atomic();
void end_atomic();
bool system_initializing();
void system_initialized();
void reboot(bool hold_in_bootloader);

4
libraries/AP_HAL_FLYMAPLE/Scheduler.cpp

@ -193,10 +193,6 @@ void FLYMAPLEScheduler::_run_timer_procs(bool called_from_isr) @@ -193,10 +193,6 @@ void FLYMAPLEScheduler::_run_timer_procs(bool called_from_isr)
_in_timer_proc = false;
}
bool FLYMAPLEScheduler::system_initializing() {
return !_initialized;
}
void FLYMAPLEScheduler::system_initialized()
{
if (_initialized) {

1
libraries/AP_HAL_FLYMAPLE/Scheduler.h

@ -46,7 +46,6 @@ public: @@ -46,7 +46,6 @@ public:
void begin_atomic();
void end_atomic();
bool system_initializing();
void system_initialized();
void reboot(bool hold_in_bootloader);

4
libraries/AP_HAL_Linux/Scheduler.cpp

@ -403,10 +403,6 @@ void Scheduler::begin_atomic() @@ -403,10 +403,6 @@ void Scheduler::begin_atomic()
void Scheduler::end_atomic()
{}
bool Scheduler::system_initializing() {
return !_initialized;
}
void Scheduler::_wait_all_threads()
{
int r = pthread_barrier_wait(&_initialized_barrier);

1
libraries/AP_HAL_Linux/Scheduler.h

@ -37,7 +37,6 @@ public: @@ -37,7 +37,6 @@ public:
void begin_atomic();
void end_atomic();
bool system_initializing();
void system_initialized();
void reboot(bool hold_in_bootloader);

4
libraries/AP_HAL_PX4/Scheduler.cpp

@ -367,10 +367,6 @@ bool PX4Scheduler::in_timerprocess() @@ -367,10 +367,6 @@ bool PX4Scheduler::in_timerprocess()
return getpid() != _main_task_pid;
}
bool PX4Scheduler::system_initializing() {
return !_initialized;
}
void PX4Scheduler::system_initialized() {
if (_initialized) {
AP_HAL::panic("PANIC: scheduler::system_initialized called"

1
libraries/AP_HAL_PX4/Scheduler.h

@ -58,7 +58,6 @@ public: @@ -58,7 +58,6 @@ public:
void reboot(bool hold_in_bootloader);
bool in_timerprocess();
bool system_initializing();
void system_initialized();
void hal_initialized() { _hal_initialized = true; }

4
libraries/AP_HAL_QURT/Scheduler.cpp

@ -272,10 +272,6 @@ bool Scheduler::in_timerprocess() @@ -272,10 +272,6 @@ bool Scheduler::in_timerprocess()
return getpid() != _main_task_pid;
}
bool Scheduler::system_initializing() {
return !_initialized;
}
void Scheduler::system_initialized() {
if (_initialized) {
AP_HAL::panic("PANIC: scheduler::system_initialized called"

1
libraries/AP_HAL_QURT/Scheduler.h

@ -32,7 +32,6 @@ public: @@ -32,7 +32,6 @@ public:
void reboot(bool hold_in_bootloader);
bool in_timerprocess();
bool system_initializing();
void system_initialized();
void hal_initialized();

4
libraries/AP_HAL_SITL/Scheduler.cpp

@ -122,10 +122,6 @@ bool Scheduler::in_timerprocess() { @@ -122,10 +122,6 @@ bool Scheduler::in_timerprocess() {
return _in_timer_proc || _in_io_proc;
}
bool Scheduler::system_initializing() {
return !_initialized;
}
void Scheduler::system_initialized() {
if (_initialized) {
AP_HAL::panic(

1
libraries/AP_HAL_SITL/Scheduler.h

@ -31,7 +31,6 @@ public: @@ -31,7 +31,6 @@ public:
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
bool system_initializing();
void system_initialized();
void reboot(bool hold_in_bootloader);

4
libraries/AP_HAL_VRBRAIN/Scheduler.cpp

@ -310,10 +310,6 @@ bool VRBRAINScheduler::in_timerprocess() @@ -310,10 +310,6 @@ bool VRBRAINScheduler::in_timerprocess()
return getpid() != _main_task_pid;
}
bool VRBRAINScheduler::system_initializing() {
return !_initialized;
}
void VRBRAINScheduler::system_initialized() {
if (_initialized) {
AP_HAL::panic("PANIC: scheduler::system_initialized called"

1
libraries/AP_HAL_VRBRAIN/Scheduler.h

@ -37,7 +37,6 @@ public: @@ -37,7 +37,6 @@ public:
void reboot(bool hold_in_bootloader);
bool in_timerprocess();
bool system_initializing();
void system_initialized();
void hal_initialized() { _hal_initialized = true; }

Loading…
Cancel
Save