mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: rename system_initialized() and add is_system_initialized()
This commit is contained in:
parent
74633e55cc
commit
526ae5d2f4
|
@ -60,7 +60,7 @@ void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const
|
||||||
_member->init();
|
_member->init();
|
||||||
|
|
||||||
callbacks->setup();
|
callbacks->setup();
|
||||||
scheduler->system_initialized();
|
scheduler->set_system_initialized();
|
||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
callbacks->loop();
|
callbacks->loop();
|
||||||
|
|
|
@ -28,7 +28,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc k)
|
||||||
void Scheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
|
void Scheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void Scheduler::system_initialized()
|
void Scheduler::set_system_initialized()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void Scheduler::reboot(bool hold_in_bootloader) {
|
void Scheduler::reboot(bool hold_in_bootloader) {
|
||||||
|
|
|
@ -13,7 +13,8 @@ public:
|
||||||
|
|
||||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
|
||||||
|
|
||||||
void system_initialized() override;
|
void set_system_initialized() override;
|
||||||
|
bool is_system_initialized() override { return true; }
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader) override;
|
void reboot(bool hold_in_bootloader) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue