mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_HAL_Scheduler: remove unused functions
Getting the time elapsed and panic are now functions in AP_HAL, so remove them from HAL class interface and it's implementations.
This commit is contained in:
parent
d343bfdc6c
commit
c5fc0deee9
@ -15,10 +15,6 @@ public:
|
|||||||
Scheduler() {}
|
Scheduler() {}
|
||||||
virtual void init(void* implspecific) = 0;
|
virtual void init(void* implspecific) = 0;
|
||||||
virtual void delay(uint16_t ms) = 0;
|
virtual void delay(uint16_t ms) = 0;
|
||||||
virtual uint32_t millis() = 0;
|
|
||||||
virtual uint32_t micros() = 0;
|
|
||||||
virtual uint64_t millis64() = 0;
|
|
||||||
virtual uint64_t micros64() = 0;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
delay for the given number of microseconds. This needs to be as
|
delay for the given number of microseconds. This needs to be as
|
||||||
@ -56,7 +52,6 @@ public:
|
|||||||
virtual bool system_initializing() = 0;
|
virtual bool system_initializing() = 0;
|
||||||
virtual void system_initialized() = 0;
|
virtual void system_initialized() = 0;
|
||||||
|
|
||||||
virtual void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN = 0;
|
|
||||||
virtual void reboot(bool hold_in_bootloader) = 0;
|
virtual void reboot(bool hold_in_bootloader) = 0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
Loading…
Reference in New Issue
Block a user