mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_HAL_FLYMAPLE: remove unused functions
This commit is contained in:
parent
420dfc7ce2
commit
f3cc27e04a
@ -93,22 +93,6 @@ void FLYMAPLEScheduler::delay(uint16_t ms)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t FLYMAPLEScheduler::millis() {
|
|
||||||
return AP_HAL::millis();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t FLYMAPLEScheduler::micros() {
|
|
||||||
return AP_HAL::micros();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint64_t FLYMAPLEScheduler::millis64() {
|
|
||||||
return AP_HAL::millis64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint64_t FLYMAPLEScheduler::micros64() {
|
|
||||||
return AP_HAL::micros64();
|
|
||||||
}
|
|
||||||
|
|
||||||
void FLYMAPLEScheduler::delay_microseconds(uint16_t us)
|
void FLYMAPLEScheduler::delay_microseconds(uint16_t us)
|
||||||
{
|
{
|
||||||
delay_us(us);
|
delay_us(us);
|
||||||
@ -222,22 +206,6 @@ void FLYMAPLEScheduler::system_initialized()
|
|||||||
_initialized = true;
|
_initialized = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLEScheduler::panic(const char *errormsg, ...) {
|
|
||||||
/* Suspend timer processes. We still want the timer event to go off
|
|
||||||
* to run the _failsafe code, however. */
|
|
||||||
// REVISIT: not tested on FLYMAPLE
|
|
||||||
va_list ap;
|
|
||||||
|
|
||||||
_timer_suspended = true;
|
|
||||||
|
|
||||||
va_start(ap, errormsg);
|
|
||||||
hal.console->vprintf(errormsg, ap);
|
|
||||||
va_end(ap);
|
|
||||||
hal.console->printf("\n");
|
|
||||||
|
|
||||||
for(;;);
|
|
||||||
}
|
|
||||||
|
|
||||||
void FLYMAPLEScheduler::reboot(bool hold_in_bootloader) {
|
void FLYMAPLEScheduler::reboot(bool hold_in_bootloader) {
|
||||||
hal.uartA->println("GOING DOWN FOR A REBOOT\r\n");
|
hal.uartA->println("GOING DOWN FOR A REBOOT\r\n");
|
||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
|
@ -28,10 +28,6 @@ public:
|
|||||||
FLYMAPLEScheduler();
|
FLYMAPLEScheduler();
|
||||||
void init(void* machtnichts);
|
void init(void* machtnichts);
|
||||||
void delay(uint16_t ms);
|
void delay(uint16_t ms);
|
||||||
uint32_t millis();
|
|
||||||
uint32_t micros();
|
|
||||||
uint64_t millis64();
|
|
||||||
uint64_t micros64();
|
|
||||||
void delay_microseconds(uint16_t us);
|
void delay_microseconds(uint16_t us);
|
||||||
void register_delay_callback(AP_HAL::Proc,
|
void register_delay_callback(AP_HAL::Proc,
|
||||||
uint16_t min_time_ms);
|
uint16_t min_time_ms);
|
||||||
@ -53,7 +49,6 @@ public:
|
|||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user