From 8ba5272b0e3fbc11ea0d855b3b03cf2e24f78af8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 May 2015 13:54:27 +1000 Subject: [PATCH] AP_Scheduler: fixed PSTR() usage --- libraries/AP_Scheduler/AP_Scheduler.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index aae884a494..e79c1c05db 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -73,7 +73,7 @@ void AP_Scheduler::run(uint16_t time_available) if (dt >= interval_ticks*2) { // we've slipped a whole run of this task! if (_debug > 1) { - hal.console->printf_P("Scheduler slip task[%u] (%u/%u/%u)\n", + hal.console->printf_P(PSTR("Scheduler slip task[%u] (%u/%u/%u)\n"), (unsigned)i, (unsigned)dt, (unsigned)interval_ticks, @@ -100,7 +100,7 @@ void AP_Scheduler::run(uint16_t time_available) if (time_taken > _task_time_allowed) { // the event overran! if (_debug > 2) { - hal.console->printf_P("Scheduler overrun task[%u] (%u/%u)\n", + hal.console->printf_P(PSTR("Scheduler overrun task[%u] (%u/%u)\n"), (unsigned)i, (unsigned)time_taken, (unsigned)_task_time_allowed);