mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_HAL_VRBRAIN: remove unused functions
This commit is contained in:
parent
783db23a0f
commit
cbaa57c7be
@ -74,26 +74,6 @@ void VRBRAINScheduler::init(void *unused)
|
|||||||
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&VRBRAIN::VRBRAINScheduler::_io_thread, this);
|
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&VRBRAIN::VRBRAINScheduler::_io_thread, this);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t VRBRAINScheduler::micros64()
|
|
||||||
{
|
|
||||||
return AP_HAL::micros64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint64_t VRBRAINScheduler::millis64()
|
|
||||||
{
|
|
||||||
return AP_HAL::millis64();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t VRBRAINScheduler::micros()
|
|
||||||
{
|
|
||||||
return AP_HAL::micros();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t VRBRAINScheduler::millis()
|
|
||||||
{
|
|
||||||
return AP_HAL::millis();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
delay for a specified number of microseconds using a semaphore wait
|
delay for a specified number of microseconds using a semaphore wait
|
||||||
*/
|
*/
|
||||||
@ -325,20 +305,6 @@ void *VRBRAINScheduler::_io_thread(void)
|
|||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void VRBRAINScheduler::panic(const char *errormsg, ...)
|
|
||||||
{
|
|
||||||
va_list ap;
|
|
||||||
|
|
||||||
va_start(ap, errormsg);
|
|
||||||
vdprintf(1, errormsg, ap);
|
|
||||||
va_end(ap);
|
|
||||||
write(1, "\n", 1);
|
|
||||||
|
|
||||||
hal.scheduler->delay_microseconds(10000);
|
|
||||||
_vrbrain_thread_should_exit = true;
|
|
||||||
exit(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
bool VRBRAINScheduler::in_timerprocess()
|
bool VRBRAINScheduler::in_timerprocess()
|
||||||
{
|
{
|
||||||
return getpid() != _main_task_pid;
|
return getpid() != _main_task_pid;
|
||||||
|
@ -27,10 +27,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);
|
||||||
void register_timer_process(AP_HAL::MemberProc);
|
void register_timer_process(AP_HAL::MemberProc);
|
||||||
@ -39,7 +35,6 @@ public:
|
|||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
|
Loading…
Reference in New Issue
Block a user