diff --git a/libraries/AP_HAL_QURT/Scheduler.h b/libraries/AP_HAL_QURT/Scheduler.h index 1c5389fe37..82ea781a64 100644 --- a/libraries/AP_HAL_QURT/Scheduler.h +++ b/libraries/AP_HAL_QURT/Scheduler.h @@ -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 { diff --git a/libraries/AP_HAL_QURT/Semaphores.h b/libraries/AP_HAL_QURT/Semaphores.h index ba7029d588..89ec68346f 100644 --- a/libraries/AP_HAL_QURT/Semaphores.h +++ b/libraries/AP_HAL_QURT/Semaphores.h @@ -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); diff --git a/libraries/AP_HAL_QURT/Util.h b/libraries/AP_HAL_QURT/Util.h index 8927f6b88e..bdf2d054f1 100644 --- a/libraries/AP_HAL_QURT/Util.h +++ b/libraries/AP_HAL_QURT/Util.h @@ -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;