Load monitor: report and log processes low on stack

This commit is contained in:
Andreas Antener
2016-11-21 14:30:51 +01:00
committed by Lorenz Meier
parent b0ee5256d5
commit 62103be7ba
5 changed files with 91 additions and 4 deletions

View File

@@ -36,6 +36,7 @@
*
* @author Jonathan Challinger <jonathan@3drobotics.com>
* @author Julian Oes <julian@oes.ch
* @author Andreas Antener <andreas@uaventure.com>
*/
#include <stdio.h>
@@ -55,6 +56,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/low_stack.h>
extern struct system_load_s system_load;
@@ -96,6 +98,15 @@ private:
/* Calculate the memory usage */
float _ram_used();
#ifdef __PX4_NUTTX
/* Calculate stack usage */
void _stack_usage();
struct low_stack_s _low_stack;
int _stack_task_index;
orb_advert_t _low_stack_pub;
#endif
bool _taskShouldExit;
bool _taskIsRunning;
struct work_s _work;
@@ -105,8 +116,12 @@ private:
hrt_abstime _last_idle_time;
};
LoadMon::LoadMon() :
#ifdef __PX4_NUTTX
_low_stack {},
_stack_task_index(0),
_low_stack_pub(nullptr),
#endif
_taskShouldExit(false),
_taskIsRunning(false),
_work{},
@@ -117,14 +132,14 @@ LoadMon::LoadMon() :
LoadMon::~LoadMon()
{
work_cancel(HPWORK, &_work);
work_cancel(LPWORK, &_work);
_taskIsRunning = false;
}
int LoadMon::start()
{
/* Schedule a cycle to start things. */
return work_queue(HPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this, 0);
return work_queue(LPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this, 0);
}
void LoadMon::stop()
@@ -147,7 +162,7 @@ void LoadMon::_cycle()
_compute();
if (!_taskShouldExit) {
work_queue(HPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this,
work_queue(LPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this,
USEC2TICK(LOAD_MON_INTERVAL_US));
}
}
@@ -168,6 +183,10 @@ void LoadMon::_compute()
_cpuload.load = 1.0f - (float)interval_idletime / (float)LOAD_MON_INTERVAL_US;
_cpuload.ram_usage = _ram_used();
#ifdef __PX4_NUTTX
_stack_usage();
#endif
if (_cpuload_pub == nullptr) {
_cpuload_pub = orb_advertise(ORB_ID(cpuload), &_cpuload);
@@ -205,6 +224,49 @@ float LoadMon::_ram_used()
#endif
}
#ifdef __PX4_NUTTX
void LoadMon::_stack_usage()
{
for (int i = _stack_task_index; i < CONFIG_MAX_TASKS; i++) {
if (system_load.tasks[i].valid && system_load.tasks[i].tcb->pid > 0) {
unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr -
(uintptr_t)system_load.tasks[i].tcb->stack_alloc_ptr;
unsigned stack_free = 0;
uint8_t *stack_sweeper = (uint8_t *)system_load.tasks[i].tcb->stack_alloc_ptr;
while (stack_free < stack_size) {
if (*stack_sweeper++ != 0xff) {
break;
}
stack_free++;
}
/*
* Found task low on stack, report and exit. Continue here in next cycle.
*/
if (stack_free < 300) {
strncpy((char *)_low_stack.task_name, system_load.tasks[i].tcb->name, low_stack_s::MAX_REPORT_TASK_NAME_LEN);
_low_stack.stack_free = stack_free;
if (_low_stack_pub == nullptr) {
_low_stack_pub = orb_advertise(ORB_ID(low_stack), &_low_stack);
} else {
orb_publish(ORB_ID(low_stack), _low_stack_pub, &_low_stack);
}
// continue at next index
_stack_task_index = i + 1;
return;
}
}
}
_stack_task_index = 0;
}
#endif
/**
* Print the correct usage.
*/