mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_HAL_SITL: remove unused functions
This commit is contained in:
parent
1de0e0a5a6
commit
783db23a0f
@ -37,31 +37,6 @@ void SITLScheduler::init(void *unused)
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t SITLScheduler::_micros64()
|
|
||||||
{
|
|
||||||
return AP_HAL::micros64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint64_t SITLScheduler::micros64()
|
|
||||||
{
|
|
||||||
return AP_HAL::micros64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t SITLScheduler::micros()
|
|
||||||
{
|
|
||||||
return AP_HAL::micros();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint64_t SITLScheduler::millis64()
|
|
||||||
{
|
|
||||||
return AP_HAL::millis64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t SITLScheduler::millis()
|
|
||||||
{
|
|
||||||
return AP_HAL::millis();
|
|
||||||
}
|
|
||||||
|
|
||||||
void SITLScheduler::delay_microseconds(uint16_t usec)
|
void SITLScheduler::delay_microseconds(uint16_t usec)
|
||||||
{
|
{
|
||||||
uint64_t start = AP_HAL::micros64();
|
uint64_t start = AP_HAL::micros64();
|
||||||
@ -240,18 +215,6 @@ void SITLScheduler::_run_io_procs(bool called_from_isr)
|
|||||||
_in_io_proc = false;
|
_in_io_proc = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITLScheduler::panic(const char *errormsg, ...)
|
|
||||||
{
|
|
||||||
va_list ap;
|
|
||||||
|
|
||||||
va_start(ap, errormsg);
|
|
||||||
hal.console->vprintf(errormsg, ap);
|
|
||||||
va_end(ap);
|
|
||||||
hal.console->printf("\n");
|
|
||||||
|
|
||||||
for(;;);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set simulation timestamp
|
set simulation timestamp
|
||||||
*/
|
*/
|
||||||
|
@ -21,10 +21,6 @@ public:
|
|||||||
|
|
||||||
void init(void *unused);
|
void init(void *unused);
|
||||||
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, uint16_t min_time_ms);
|
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
||||||
|
|
||||||
@ -41,7 +37,6 @@ public:
|
|||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
|
||||||
|
|
||||||
bool interrupts_are_blocked(void) {
|
bool interrupts_are_blocked(void) {
|
||||||
return _nested_atomic_ctr != 0;
|
return _nested_atomic_ctr != 0;
|
||||||
@ -52,8 +47,6 @@ public:
|
|||||||
}
|
}
|
||||||
void sitl_end_atomic();
|
void sitl_end_atomic();
|
||||||
|
|
||||||
// callable from interrupt handler
|
|
||||||
static uint64_t _micros64();
|
|
||||||
static void timer_event() {
|
static void timer_event() {
|
||||||
_run_timer_procs(true);
|
_run_timer_procs(true);
|
||||||
_run_io_procs(true);
|
_run_io_procs(true);
|
||||||
|
Loading…
Reference in New Issue
Block a user