mirror of https://github.com/ArduPilot/ardupilot
HAL_QURT: small cleanups
thanks to Lucas for finding these
This commit is contained in:
parent
e46f23f538
commit
fa2a39f6c6
|
@ -13,11 +13,6 @@
|
|||
#define APM_TIMER_PRIORITY 181
|
||||
#define APM_UART_PRIORITY 60
|
||||
#define APM_IO_PRIORITY 58
|
||||
#define APM_SHELL_PRIORITY 57
|
||||
#define APM_OVERTIME_PRIORITY 10
|
||||
#define APM_STARTUP_PRIORITY 10
|
||||
|
||||
#define APM_MAIN_THREAD_STACK_SIZE 16384
|
||||
|
||||
/* Scheduler implementation: */
|
||||
class QURT::Scheduler : public AP_HAL::Scheduler {
|
||||
|
|
|
@ -9,9 +9,7 @@
|
|||
class QURT::Semaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
Semaphore() {
|
||||
HAP_PRINTF("%s constructor", __FUNCTION__);
|
||||
pthread_mutex_init(&_lock, NULL);
|
||||
HAP_PRINTF("%s constructor2", __FUNCTION__);
|
||||
}
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
|
|
|
@ -20,9 +20,7 @@
|
|||
|
||||
class QURT::Util : public AP_HAL::Util {
|
||||
public:
|
||||
Util(void) {
|
||||
HAP_PRINTF("%s constructor", __FUNCTION__);
|
||||
}
|
||||
Util(void) {}
|
||||
bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; }
|
||||
|
||||
uint32_t available_memory(void) override;
|
||||
|
|
Loading…
Reference in New Issue