Browse Source

HAL_PX4: print overtime message on stuck task

this should make it easier to narrow down stuck task bugs
master
Andrew Tridgell 11 years ago
parent
commit
849c4905fb
  1. 8
      libraries/AP_HAL_PX4/HAL_PX4_Class.cpp
  2. 10
      libraries/AP_HAL_PX4/Scheduler.cpp

8
libraries/AP_HAL_PX4/HAL_PX4_Class.cpp

@ -86,7 +86,7 @@ HAL_PX4::HAL_PX4() : @@ -86,7 +86,7 @@ HAL_PX4::HAL_PX4() :
bool _px4_thread_should_exit = false; /**< Daemon exit flag */
static bool thread_running = false; /**< Daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
static bool ran_overtime;
bool px4_ran_overtime;
extern const AP_HAL::HAL& hal;
@ -109,7 +109,7 @@ static void set_priority(uint8_t priority) @@ -109,7 +109,7 @@ static void set_priority(uint8_t priority)
static void loop_overtime(void *)
{
set_priority(APM_OVERTIME_PRIORITY);
ran_overtime = true;
px4_ran_overtime = true;
}
static int main_loop(int argc, char **argv)
@ -165,14 +165,14 @@ static int main_loop(int argc, char **argv) @@ -165,14 +165,14 @@ static int main_loop(int argc, char **argv)
loop();
if (ran_overtime) {
if (px4_ran_overtime) {
/*
we ran over 1s in loop(), and our priority was lowered
to let a driver run. Set it back to high priority now.
*/
set_priority(APM_MAIN_PRIORITY);
perf_count(perf_overrun);
ran_overtime = false;
px4_ran_overtime = false;
}
perf_end(perf_loop);

10
libraries/AP_HAL_PX4/Scheduler.cpp

@ -22,6 +22,7 @@ @@ -22,6 +22,7 @@
#include "Storage.h"
#include "RCOutput.h"
#include "RCInput.h"
#include <AP_Scheduler.h>
using namespace PX4;
@ -229,8 +230,11 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread) @@ -229,8 +230,11 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
_in_timer_proc = false;
}
extern bool px4_ran_overtime;
void *PX4Scheduler::_timer_thread(void)
{
uint32_t last_ran_overtime = 0;
while (!_hal_initialized) {
poll(NULL, 0, 1);
}
@ -247,6 +251,12 @@ void *PX4Scheduler::_timer_thread(void) @@ -247,6 +251,12 @@ void *PX4Scheduler::_timer_thread(void)
// process any pending RC input requests
((PX4RCInput *)hal.rcin)->_timer_tick();
if (px4_ran_overtime && millis() - last_ran_overtime > 2000) {
last_ran_overtime = millis();
printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
}
}
return NULL;
}

Loading…
Cancel
Save