mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:15:55 +08:00
NuttX cpuload monitoring optimization
- Nuttx only process all suspend & resume scheduling notes when top is running, otherwise only track IDLE - convert cpuload and print load to c++ - delete unused fields from print_load struct - update hrt_store_absolute_time (previous unused)
This commit is contained in:
@@ -124,7 +124,7 @@ __EXPORT extern hrt_abstime hrt_elapsed_time_atomic(const volatile hrt_abstime *
|
||||
*
|
||||
* This function ensures that the timestamp cannot be seen half-written by an interrupt handler.
|
||||
*/
|
||||
__EXPORT extern hrt_abstime hrt_store_absolute_time(volatile hrt_abstime *now);
|
||||
__EXPORT extern void hrt_store_absolute_time(volatile hrt_abstime *time);
|
||||
|
||||
#ifdef __PX4_QURT
|
||||
/**
|
||||
|
||||
@@ -42,15 +42,8 @@ set(SRCS
|
||||
|
||||
if(${PX4_PLATFORM} STREQUAL "nuttx")
|
||||
list(APPEND SRCS
|
||||
cpuload.c
|
||||
cpuload.h
|
||||
print_load_nuttx.c
|
||||
otp.c
|
||||
)
|
||||
else()
|
||||
list(APPEND SRCS
|
||||
print_load_posix.c
|
||||
)
|
||||
endif()
|
||||
|
||||
px4_add_library(systemlib ${SRCS})
|
||||
|
||||
@@ -1,185 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file cpuload.c
|
||||
*
|
||||
* Measurement of CPU load of each individual task.
|
||||
*
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
* @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
||||
*/
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
//#include <arch/arch.h>
|
||||
|
||||
//#include <debug.h>
|
||||
|
||||
#include <sys/time.h>
|
||||
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "cpuload.h"
|
||||
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
|
||||
# include <nuttx/sched_note.h>
|
||||
|
||||
void sched_note_suspend(FAR struct tcb_s *tcb);
|
||||
void sched_note_resume(FAR struct tcb_s *tcb);
|
||||
|
||||
__EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb);
|
||||
|
||||
__EXPORT struct system_load_s system_load;
|
||||
|
||||
extern FAR struct tcb_s *sched_gettcb(pid_t pid);
|
||||
|
||||
void cpuload_initialize_once()
|
||||
{
|
||||
system_load.start_time = hrt_absolute_time();
|
||||
int i;
|
||||
|
||||
for (i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
system_load.tasks[i].valid = false;
|
||||
}
|
||||
|
||||
int static_tasks_count = 2; // there are at least 2 threads that should be initialized statically - "idle" and "init"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
static_tasks_count++; // include paging thread in initialization
|
||||
#endif /* CONFIG_PAGING */
|
||||
#if CONFIG_SCHED_WORKQUEUE
|
||||
static_tasks_count++; // include high priority work0 thread in initialization
|
||||
#endif /* CONFIG_SCHED_WORKQUEUE */
|
||||
#if CONFIG_SCHED_LPWORK
|
||||
static_tasks_count++; // include low priority work1 thread in initialization
|
||||
#endif /* CONFIG_SCHED_WORKQUEUE */
|
||||
|
||||
// perform static initialization of "system" threads
|
||||
for (system_load.total_count = 0; system_load.total_count < static_tasks_count; system_load.total_count++) {
|
||||
system_load.tasks[system_load.total_count].total_runtime = 0;
|
||||
system_load.tasks[system_load.total_count].curr_start_time = 0;
|
||||
system_load.tasks[system_load.total_count].tcb = sched_gettcb(
|
||||
system_load.total_count); // it is assumed that these static threads have consecutive PIDs
|
||||
system_load.tasks[system_load.total_count].valid = true;
|
||||
}
|
||||
|
||||
system_load.initialized = true;
|
||||
}
|
||||
|
||||
void sched_note_start(FAR struct tcb_s *tcb)
|
||||
{
|
||||
/* search first free slot */
|
||||
int i;
|
||||
|
||||
if (system_load.initialized) {
|
||||
for (i = 1; i < CONFIG_MAX_TASKS; i++) {
|
||||
if (!system_load.tasks[i].valid) {
|
||||
/* slot is available */
|
||||
system_load.tasks[i].total_runtime = 0;
|
||||
system_load.tasks[i].curr_start_time = 0;
|
||||
system_load.tasks[i].tcb = tcb;
|
||||
system_load.tasks[i].valid = true;
|
||||
system_load.total_count++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void sched_note_stop(FAR struct tcb_s *tcb)
|
||||
{
|
||||
int i;
|
||||
|
||||
if (system_load.initialized) {
|
||||
for (i = 1; i < CONFIG_MAX_TASKS; i++) {
|
||||
if (system_load.tasks[i].tcb != 0 && system_load.tasks[i].tcb->pid == tcb->pid) {
|
||||
/* mark slot as fee */
|
||||
system_load.tasks[i].valid = false;
|
||||
system_load.tasks[i].total_runtime = 0;
|
||||
system_load.tasks[i].curr_start_time = 0;
|
||||
system_load.tasks[i].tcb = NULL;
|
||||
system_load.total_count--;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void sched_note_suspend(FAR struct tcb_s *tcb)
|
||||
{
|
||||
|
||||
if (system_load.initialized) {
|
||||
uint64_t new_time = hrt_absolute_time();
|
||||
|
||||
for (int i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
/* Task ending its current scheduling run */
|
||||
if (system_load.tasks[i].valid && system_load.tasks[i].tcb != 0 && system_load.tasks[i].tcb->pid == tcb->pid) {
|
||||
system_load.tasks[i].total_runtime += new_time - system_load.tasks[i].curr_start_time;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void sched_note_resume(FAR struct tcb_s *tcb)
|
||||
{
|
||||
|
||||
if (system_load.initialized) {
|
||||
uint64_t new_time = hrt_absolute_time();
|
||||
|
||||
for (int i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
if (system_load.tasks[i].valid && system_load.tasks[i].tcb->pid == tcb->pid) {
|
||||
// curr_start_time is accessed from an IRQ handler (in logger), so we need
|
||||
// to make the update atomic
|
||||
irqstate_t irq_state = px4_enter_critical_section();
|
||||
system_load.tasks[i].curr_start_time = new_time;
|
||||
px4_leave_critical_section(irq_state);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#else
|
||||
__EXPORT struct system_load_s system_load;
|
||||
#endif
|
||||
#endif /* CONFIG_SCHED_INSTRUMENTATION */
|
||||
@@ -1,68 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
|
||||
#include <sched.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
struct system_load_taskinfo_s {
|
||||
uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
|
||||
uint64_t curr_start_time; ///< Start time of the current scheduling slot
|
||||
#ifdef __PX4_NUTTX
|
||||
FAR struct tcb_s *tcb; ///<
|
||||
#endif
|
||||
bool valid; ///< Task is currently active / valid
|
||||
};
|
||||
|
||||
struct system_load_s {
|
||||
uint64_t start_time; ///< Global start time of measurements
|
||||
struct system_load_taskinfo_s tasks[CONFIG_MAX_TASKS];
|
||||
uint8_t initialized;
|
||||
int total_count;
|
||||
int running_count;
|
||||
int sleeping_count;
|
||||
};
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT extern struct system_load_s system_load;
|
||||
|
||||
__EXPORT void cpuload_initialize_once(void);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
#endif
|
||||
@@ -1,398 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file printload.c
|
||||
*
|
||||
* Print the current system load.
|
||||
*
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/printload.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#if defined(BOARD_DMA_ALLOC_POOL_SIZE)
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
#endif /* BOARD_DMA_ALLOC_POOL_SIZE */
|
||||
|
||||
#if defined(CONFIG_SCHED_INSTRUMENTATION)
|
||||
|
||||
#if !defined(CONFIG_TASK_NAME_SIZE)
|
||||
#error print_load_nuttx requires CONFIG_TASK_NAME_SIZE
|
||||
#endif
|
||||
|
||||
#if !defined(CONFIG_STACK_COLORATION)
|
||||
#error print_load_nuttx requires CONFIG_STACK_COLORATION
|
||||
#endif
|
||||
|
||||
extern struct system_load_s system_load;
|
||||
|
||||
#define CL "\033[K" // clear line
|
||||
|
||||
void init_print_load_s(uint64_t t, struct print_load_s *s)
|
||||
{
|
||||
|
||||
s->total_user_time = 0;
|
||||
|
||||
s->running_count = 0;
|
||||
s->blocked_count = 0;
|
||||
|
||||
s->new_time = t;
|
||||
s->interval_start_time = t;
|
||||
|
||||
for (int i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
s->last_times[i] = 0;
|
||||
}
|
||||
|
||||
s->interval_time_ms_inv = 0.f;
|
||||
}
|
||||
|
||||
static const char *
|
||||
tstate_name(const tstate_t s)
|
||||
{
|
||||
switch (s) {
|
||||
case TSTATE_TASK_INVALID:
|
||||
return "init";
|
||||
|
||||
case TSTATE_TASK_PENDING:
|
||||
return "PEND";
|
||||
|
||||
case TSTATE_TASK_READYTORUN:
|
||||
return "READY";
|
||||
|
||||
case TSTATE_TASK_RUNNING:
|
||||
return "RUN";
|
||||
|
||||
case TSTATE_TASK_INACTIVE:
|
||||
return "inact";
|
||||
|
||||
case TSTATE_WAIT_SEM:
|
||||
return "w:sem";
|
||||
#ifndef CONFIG_DISABLE_SIGNALS
|
||||
|
||||
case TSTATE_WAIT_SIG:
|
||||
return "w:sig";
|
||||
#endif
|
||||
#ifndef CONFIG_DISABLE_MQUEUE
|
||||
|
||||
case TSTATE_WAIT_MQNOTEMPTY:
|
||||
return "w:mqe";
|
||||
|
||||
case TSTATE_WAIT_MQNOTFULL:
|
||||
return "w:mqf";
|
||||
#endif
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
case TSTATE_WAIT_PAGEFILL:
|
||||
return "w:pgf";
|
||||
#endif
|
||||
|
||||
default:
|
||||
return "ERROR";
|
||||
}
|
||||
}
|
||||
|
||||
void print_load_buffer(uint64_t t, char *buffer, int buffer_length, print_load_callback_f cb, void *user,
|
||||
struct print_load_s *print_state)
|
||||
{
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wformat" // NuttX uses a different printf format
|
||||
#pragma GCC diagnostic ignored "-Wformat-extra-args"
|
||||
print_state->new_time = t;
|
||||
|
||||
int i;
|
||||
uint64_t curr_time_us;
|
||||
uint64_t idle_time_us;
|
||||
float idle_load = 0.f;
|
||||
|
||||
curr_time_us = t;
|
||||
idle_time_us = system_load.tasks[0].total_runtime;
|
||||
|
||||
if (print_state->new_time > print_state->interval_start_time) {
|
||||
print_state->interval_time_ms_inv = 1.f / ((float)((print_state->new_time - print_state->interval_start_time) / 1000));
|
||||
|
||||
/* header for task list */
|
||||
snprintf(buffer, buffer_length, "%4s %-*s %8s %6s %11s %10s %-5s %2s",
|
||||
"PID",
|
||||
CONFIG_TASK_NAME_SIZE, "COMMAND",
|
||||
"CPU(ms)",
|
||||
"CPU(%)",
|
||||
"USED/STACK",
|
||||
"PRIO(BASE)",
|
||||
#if CONFIG_RR_INTERVAL > 0
|
||||
"TSLICE",
|
||||
#else
|
||||
"STATE",
|
||||
#endif
|
||||
"FD"
|
||||
);
|
||||
cb(user);
|
||||
|
||||
}
|
||||
|
||||
print_state->running_count = 0;
|
||||
print_state->blocked_count = 0;
|
||||
print_state->total_user_time = 0;
|
||||
|
||||
// create a copy of the runtimes because this could be updated during the print output
|
||||
uint32_t total_runtime[CONFIG_MAX_TASKS];
|
||||
|
||||
for (i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
total_runtime[i] = (uint32_t)(system_load.tasks[i].total_runtime / 1000);
|
||||
}
|
||||
|
||||
for (i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
|
||||
sched_lock(); // need to lock the tcb access (but make it as short as possible)
|
||||
|
||||
if (!system_load.tasks[i].valid) {
|
||||
sched_unlock();
|
||||
continue;
|
||||
}
|
||||
|
||||
uint64_t interval_runtime;
|
||||
unsigned tcb_pid = system_load.tasks[i].tcb->pid;
|
||||
size_t stack_size = system_load.tasks[i].tcb->adj_stack_size;
|
||||
ssize_t stack_free = 0;
|
||||
char tcb_name[CONFIG_TASK_NAME_SIZE + 1];
|
||||
strncpy(tcb_name, system_load.tasks[i].tcb->name, CONFIG_TASK_NAME_SIZE + 1);
|
||||
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
|
||||
if (system_load.tasks[i].tcb->pid == 0) {
|
||||
stack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
|
||||
stack_free = up_check_intstack_remain();
|
||||
|
||||
} else {
|
||||
stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
|
||||
}
|
||||
|
||||
#else
|
||||
stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
|
||||
#endif
|
||||
|
||||
#if CONFIG_ARCH_BOARD_SIM || !defined(CONFIG_PRIORITY_INHERITANCE)
|
||||
#else
|
||||
unsigned tcb_base_priority = system_load.tasks[i].tcb->base_priority;
|
||||
#endif
|
||||
#if CONFIG_RR_INTERVAL > 0
|
||||
unsigned tcb_timeslice = system_load.tasks[i].tcb->timeslice;
|
||||
#endif
|
||||
unsigned tcb_task_state = system_load.tasks[i].tcb->task_state;
|
||||
unsigned tcb_sched_priority = system_load.tasks[i].tcb->sched_priority;
|
||||
|
||||
unsigned int tcb_num_used_fds = 0; // number of used file descriptors
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
FAR struct task_group_s *group = system_load.tasks[i].tcb->group;
|
||||
|
||||
if (group) {
|
||||
for (int fd_index = 0; fd_index < CONFIG_NFILE_DESCRIPTORS; ++fd_index) {
|
||||
if (group->tg_filelist.fl_files[fd_index].f_inode) {
|
||||
++tcb_num_used_fds;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
sched_unlock();
|
||||
|
||||
switch (tcb_task_state) {
|
||||
case TSTATE_TASK_PENDING:
|
||||
case TSTATE_TASK_READYTORUN:
|
||||
case TSTATE_TASK_RUNNING:
|
||||
print_state->running_count++;
|
||||
break;
|
||||
|
||||
#ifndef CONFIG_DISABLE_SIGNALS
|
||||
|
||||
case TSTATE_WAIT_SIG:
|
||||
#endif
|
||||
#ifndef CONFIG_DISABLE_MQUEUE
|
||||
case TSTATE_WAIT_MQNOTEMPTY:
|
||||
case TSTATE_WAIT_MQNOTFULL:
|
||||
#endif
|
||||
#ifdef CONFIG_PAGING
|
||||
case TSTATE_WAIT_PAGEFILL:
|
||||
#endif
|
||||
case TSTATE_TASK_INVALID:
|
||||
case TSTATE_TASK_INACTIVE:
|
||||
case TSTATE_WAIT_SEM:
|
||||
print_state->blocked_count++;
|
||||
break;
|
||||
}
|
||||
|
||||
interval_runtime = (print_state->last_times[i] > 0 && total_runtime[i] > print_state->last_times[i])
|
||||
? (total_runtime[i] - print_state->last_times[i]) : 0;
|
||||
|
||||
print_state->last_times[i] = total_runtime[i];
|
||||
|
||||
float current_load = 0.f;
|
||||
|
||||
if (print_state->new_time > print_state->interval_start_time) {
|
||||
current_load = interval_runtime * print_state->interval_time_ms_inv;
|
||||
|
||||
if (tcb_pid != 0) {
|
||||
print_state->total_user_time += interval_runtime;
|
||||
|
||||
} else {
|
||||
idle_load = current_load;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
if (print_state->new_time <= print_state->interval_start_time) {
|
||||
continue; // not enough data yet
|
||||
}
|
||||
|
||||
// print output
|
||||
int print_len = snprintf(buffer, buffer_length, "%4d %-*s %8d %2d.%03d %5u/%5u %3u (%3u) ",
|
||||
tcb_pid,
|
||||
CONFIG_TASK_NAME_SIZE, tcb_name,
|
||||
total_runtime[i],
|
||||
(int)(current_load * 100.0f),
|
||||
(int)((current_load * 100.0f - (int)(current_load * 100.0f)) * 1000),
|
||||
stack_size - stack_free,
|
||||
stack_size,
|
||||
tcb_sched_priority,
|
||||
#if CONFIG_ARCH_BOARD_SIM || !defined(CONFIG_PRIORITY_INHERITANCE)
|
||||
0);
|
||||
#else
|
||||
tcb_base_priority);
|
||||
#endif
|
||||
#if CONFIG_RR_INTERVAL > 0
|
||||
/* print scheduling info with RR time slice */
|
||||
snprintf(buffer + print_len, buffer_length - print_len, " %5d %2d", tcb_timeslice, tcb_num_used_fds);
|
||||
(void)tstate_name(TSTATE_TASK_INVALID); // Stop not used warning
|
||||
#else
|
||||
// print task state instead
|
||||
snprintf(buffer + print_len, buffer_length - print_len, " %-5s %2d", tstate_name(tcb_task_state), tcb_num_used_fds);
|
||||
#endif
|
||||
cb(user);
|
||||
}
|
||||
|
||||
if (print_state->new_time <= print_state->interval_start_time) {
|
||||
// first run, not enough data yet
|
||||
return;
|
||||
}
|
||||
|
||||
// Print footer
|
||||
buffer[0] = 0;
|
||||
cb(user);
|
||||
float task_load;
|
||||
float sched_load;
|
||||
|
||||
task_load = (float)(print_state->total_user_time) * print_state->interval_time_ms_inv;
|
||||
|
||||
/* this can happen if one tasks total runtime was not computed
|
||||
correctly by the scheduler instrumentation TODO */
|
||||
if (task_load > (1.f - idle_load)) {
|
||||
task_load = (1.f - idle_load);
|
||||
}
|
||||
|
||||
sched_load = 1.f - idle_load - task_load;
|
||||
|
||||
snprintf(buffer, buffer_length, "Processes: %d total, %d running, %d sleeping, max FDs: %d",
|
||||
system_load.total_count,
|
||||
print_state->running_count,
|
||||
print_state->blocked_count,
|
||||
CONFIG_NFILE_DESCRIPTORS);
|
||||
cb(user);
|
||||
snprintf(buffer, buffer_length, "CPU usage: %.2f%% tasks, %.2f%% sched, %.2f%% idle",
|
||||
(double)(task_load * 100.f),
|
||||
(double)(sched_load * 100.f),
|
||||
(double)(idle_load * 100.f));
|
||||
cb(user);
|
||||
#if defined(BOARD_DMA_ALLOC_POOL_SIZE)
|
||||
uint16_t dma_total;
|
||||
uint16_t dma_used;
|
||||
uint16_t dma_peak_used;
|
||||
|
||||
if (board_get_dma_usage(&dma_total, &dma_used, &dma_peak_used) >= 0) {
|
||||
snprintf(buffer, buffer_length, "DMA Memory: %d total, %d used %d peak",
|
||||
dma_total,
|
||||
dma_used,
|
||||
dma_peak_used);
|
||||
cb(user);
|
||||
}
|
||||
|
||||
#endif
|
||||
snprintf(buffer, buffer_length, "Uptime: %.3fs total, %.3fs idle",
|
||||
(double)curr_time_us / 1000000.d,
|
||||
(double)idle_time_us / 1000000.d);
|
||||
cb(user);
|
||||
|
||||
print_state->interval_start_time = print_state->new_time;
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
}
|
||||
|
||||
|
||||
struct print_load_callback_data_s {
|
||||
int fd;
|
||||
char buffer[140];
|
||||
};
|
||||
|
||||
static void print_load_callback(void *user)
|
||||
{
|
||||
char *clear_line = "";
|
||||
struct print_load_callback_data_s *data = (struct print_load_callback_data_s *)user;
|
||||
|
||||
if (data->fd == 1) {
|
||||
clear_line = CL;
|
||||
}
|
||||
|
||||
dprintf(data->fd, "%s%s\n", clear_line, data->buffer);
|
||||
}
|
||||
|
||||
void print_load(uint64_t t, int fd, struct print_load_s *print_state)
|
||||
{
|
||||
/* print system information */
|
||||
if (fd == 1) {
|
||||
dprintf(fd, "\033[H"); /* move cursor home and clear screen */
|
||||
}
|
||||
|
||||
struct print_load_callback_data_s data;
|
||||
|
||||
data.fd = fd;
|
||||
|
||||
print_load_buffer(t, data.buffer, sizeof(data.buffer), print_load_callback, &data, print_state);
|
||||
}
|
||||
|
||||
#endif // if CONFIG_SCHED_INSTRUMENTATION
|
||||
@@ -1,183 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015-2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file print_load_posix.c
|
||||
*
|
||||
* Print the current system load.
|
||||
*
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/posix.h>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/printload.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#ifdef __PX4_DARWIN
|
||||
#include <mach/mach.h>
|
||||
#endif
|
||||
|
||||
#ifdef __PX4_QURT
|
||||
// dprintf is not available on QURT. Use the usual output to mini-dm.
|
||||
#define dprintf(_fd, _text, ...) ((_fd) == 1 ? PX4_INFO((_text), ##__VA_ARGS__) : (void)(_fd))
|
||||
#endif
|
||||
|
||||
extern struct system_load_s system_load;
|
||||
|
||||
#define CL "\033[K" // clear line
|
||||
|
||||
void init_print_load_s(uint64_t t, struct print_load_s *s)
|
||||
{
|
||||
|
||||
s->total_user_time = 0;
|
||||
|
||||
s->running_count = 0;
|
||||
s->blocked_count = 0;
|
||||
|
||||
s->new_time = t;
|
||||
s->interval_start_time = t;
|
||||
|
||||
for (int i = 0; i < CONFIG_MAX_TASKS; i++) {
|
||||
s->last_times[i] = 0;
|
||||
}
|
||||
|
||||
s->interval_time_ms_inv = 0.f;
|
||||
}
|
||||
|
||||
void print_load(uint64_t t, int fd, struct print_load_s *print_state)
|
||||
{
|
||||
char *clear_line = "";
|
||||
|
||||
/* print system information */
|
||||
if (fd == 1) {
|
||||
dprintf(fd, "\033[H"); /* move cursor home and clear screen */
|
||||
clear_line = CL;
|
||||
}
|
||||
|
||||
#if defined(__PX4_LINUX) || defined(__PX4_CYGWIN) || defined(__PX4_QURT)
|
||||
dprintf(fd, "%sTOP NOT IMPLEMENTED ON LINUX, QURT, WINDOWS (ONLY ON NUTTX, APPLE)\n", clear_line);
|
||||
|
||||
#elif defined(__PX4_DARWIN)
|
||||
pid_t pid = getpid(); //-- this is the process id you need info for
|
||||
task_t task_handle;
|
||||
task_for_pid(mach_task_self(), pid, &task_handle);
|
||||
|
||||
task_info_data_t tinfo;
|
||||
mach_msg_type_number_t th_info_cnt;
|
||||
|
||||
th_info_cnt = TASK_INFO_MAX;
|
||||
kern_return_t kr = task_info(task_handle, TASK_BASIC_INFO, (task_info_t)tinfo, &th_info_cnt);
|
||||
|
||||
if (kr != KERN_SUCCESS) {
|
||||
return;
|
||||
}
|
||||
|
||||
thread_array_t thread_list;
|
||||
mach_msg_type_number_t th_cnt;
|
||||
|
||||
thread_info_data_t th_info_data;
|
||||
mach_msg_type_number_t thread_info_count;
|
||||
|
||||
thread_basic_info_t basic_info_th;
|
||||
uint32_t stat_thread = 0;
|
||||
|
||||
// get all threads of the PX4 main task
|
||||
kr = task_threads(task_handle, &thread_list, &th_cnt);
|
||||
|
||||
if (kr != KERN_SUCCESS) {
|
||||
PX4_WARN("ERROR getting thread list");
|
||||
return;
|
||||
}
|
||||
|
||||
if (th_cnt > 0) {
|
||||
stat_thread += th_cnt;
|
||||
}
|
||||
|
||||
long tot_sec = 0;
|
||||
long tot_usec = 0;
|
||||
long tot_cpu = 0;
|
||||
|
||||
dprintf(fd, "%sThreads: %d total\n",
|
||||
clear_line,
|
||||
th_cnt);
|
||||
|
||||
for (unsigned j = 0; j < th_cnt; j++) {
|
||||
thread_info_count = THREAD_INFO_MAX;
|
||||
kr = thread_info(thread_list[j], THREAD_BASIC_INFO,
|
||||
(thread_info_t)th_info_data, &thread_info_count);
|
||||
|
||||
if (kr != KERN_SUCCESS) {
|
||||
PX4_WARN("ERROR getting thread info");
|
||||
continue;
|
||||
}
|
||||
|
||||
basic_info_th = (thread_basic_info_t)th_info_data;
|
||||
|
||||
if (!(basic_info_th->flags & TH_FLAGS_IDLE)) {
|
||||
tot_sec = tot_sec + basic_info_th->user_time.seconds + basic_info_th->system_time.seconds;
|
||||
tot_usec = tot_usec + basic_info_th->system_time.microseconds + basic_info_th->system_time.microseconds;
|
||||
tot_cpu = tot_cpu + basic_info_th->cpu_usage;
|
||||
}
|
||||
|
||||
// char tname[128];
|
||||
|
||||
// int ret = pthread_getname_np(pthread_t *thread,
|
||||
// const char *name, size_t len);
|
||||
|
||||
dprintf(fd, "thread %d\t\t %d\n", j, basic_info_th->cpu_usage);
|
||||
}
|
||||
|
||||
kr = vm_deallocate(mach_task_self(), (vm_offset_t)thread_list,
|
||||
th_cnt * sizeof(thread_t));
|
||||
|
||||
if (kr != KERN_SUCCESS) {
|
||||
PX4_WARN("ERROR cleaning up thread info");
|
||||
return;
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void print_load_buffer(uint64_t t, char *buffer, int buffer_length, print_load_callback_f cb, void *user,
|
||||
struct print_load_s *print_state)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
@@ -1,79 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file printload.h
|
||||
*
|
||||
* Print the current system load.
|
||||
*
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#ifndef CONFIG_MAX_TASKS
|
||||
#define CONFIG_MAX_TASKS 64
|
||||
#endif
|
||||
|
||||
struct print_load_s {
|
||||
uint64_t total_user_time;
|
||||
|
||||
int running_count;
|
||||
int blocked_count;
|
||||
|
||||
uint64_t new_time;
|
||||
uint64_t interval_start_time;
|
||||
uint32_t last_times[CONFIG_MAX_TASKS]; // in [ms]. This wraps if a process needs more than 49 days of CPU
|
||||
float interval_time_ms_inv;
|
||||
};
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT void init_print_load_s(uint64_t t, struct print_load_s *s);
|
||||
|
||||
__EXPORT void print_load(uint64_t t, int fd, struct print_load_s *print_state);
|
||||
|
||||
|
||||
typedef void (*print_load_callback_f)(void *user);
|
||||
|
||||
/**
|
||||
* Print load to a buffer, and call cb after each written line (buffer will not include '\n')
|
||||
*/
|
||||
void print_load_buffer(uint64_t t, char *buffer, int buffer_length, print_load_callback_f cb, void *user,
|
||||
struct print_load_s *print_state);
|
||||
|
||||
__END_DECLS
|
||||
@@ -40,7 +40,7 @@
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <px4_platform/cpuload.h>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/cpuload.h>
|
||||
#include <uORB/topics/task_stack_info.h>
|
||||
|
||||
@@ -53,6 +53,7 @@
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <mathlib/math/Limits.hpp>
|
||||
#include <px4_platform/cpuload.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
@@ -1225,6 +1226,11 @@ void Logger::start_log_file(LogType type)
|
||||
return;
|
||||
}
|
||||
|
||||
if (type == LogType::Full) {
|
||||
// initialize cpu load as early as possible to get more data
|
||||
initialize_load_output(PrintLoadReason::Preflight);
|
||||
}
|
||||
|
||||
PX4_INFO("Start file log (type: %s)", log_type_str(type));
|
||||
|
||||
char file_name[LOG_DIR_LEN] = "";
|
||||
@@ -1260,8 +1266,6 @@ void Logger::start_log_file(LogType type)
|
||||
if (type == LogType::Full) {
|
||||
/* reset performance counters to get in-flight min and max values in post flight log */
|
||||
perf_reset_all();
|
||||
|
||||
initialize_load_output(PrintLoadReason::Preflight);
|
||||
}
|
||||
|
||||
_statistics[(int)type].start_time_file = hrt_absolute_time();
|
||||
@@ -1289,6 +1293,9 @@ void Logger::start_log_mavlink()
|
||||
return;
|
||||
}
|
||||
|
||||
// initialize cpu load as early as possible to get more data
|
||||
initialize_load_output(PrintLoadReason::Preflight);
|
||||
|
||||
PX4_INFO("Start mavlink log");
|
||||
|
||||
_writer.start_log_mavlink();
|
||||
@@ -1304,8 +1311,6 @@ void Logger::start_log_mavlink()
|
||||
_writer.set_need_reliable_transfer(false);
|
||||
_writer.unselect_write_backend();
|
||||
_writer.notify();
|
||||
|
||||
initialize_load_output(PrintLoadReason::Preflight);
|
||||
}
|
||||
|
||||
void Logger::stop_log_mavlink()
|
||||
@@ -1388,16 +1393,8 @@ void Logger::print_load_callback(void *user)
|
||||
|
||||
void Logger::initialize_load_output(PrintLoadReason reason)
|
||||
{
|
||||
perf_callback_data_t callback_data;
|
||||
callback_data.logger = this;
|
||||
callback_data.counter = 0;
|
||||
callback_data.buffer = nullptr;
|
||||
char buffer[140];
|
||||
hrt_abstime curr_time = hrt_absolute_time();
|
||||
init_print_load_s(curr_time, &_load);
|
||||
// this will not yet print anything
|
||||
print_load_buffer(curr_time, buffer, sizeof(buffer), print_load_callback, &callback_data, &_load);
|
||||
_next_load_print = curr_time + 1000000;
|
||||
init_print_load(&_load);
|
||||
_next_load_print = hrt_absolute_time() + 1_s;
|
||||
_print_load_reason = reason;
|
||||
}
|
||||
|
||||
@@ -1412,11 +1409,11 @@ void Logger::write_load_output()
|
||||
callback_data.logger = this;
|
||||
callback_data.counter = 0;
|
||||
callback_data.buffer = buffer;
|
||||
hrt_abstime curr_time = hrt_absolute_time();
|
||||
_writer.set_need_reliable_transfer(true);
|
||||
// TODO: maybe we should restrict the output to a selected backend (eg. when file logging is running
|
||||
// and mavlink log is started, this will be added to the file as well)
|
||||
print_load_buffer(curr_time, buffer, sizeof(buffer), print_load_callback, &callback_data, &_load);
|
||||
print_load_buffer(buffer, sizeof(buffer), print_load_callback, &callback_data, &_load);
|
||||
cpuload_monitor_stop();
|
||||
_writer.set_need_reliable_transfer(false);
|
||||
}
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <version/version.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/printload.h>
|
||||
#include <px4_platform_common/printload.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include <sched.h>
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <px4_platform/cpuload.h>
|
||||
#endif /* __PX4_NUTTX */
|
||||
|
||||
namespace px4
|
||||
|
||||
@@ -33,10 +33,11 @@
|
||||
px4_add_module(
|
||||
MODULE systemcmds__top
|
||||
MAIN top
|
||||
STACK_MAIN 4096
|
||||
PRIORITY
|
||||
"SCHED_PRIORITY_MAX - 16" # max priority below high priority WQ threads
|
||||
SRCS
|
||||
top.c
|
||||
top.cpp
|
||||
DEPENDS
|
||||
systemlib
|
||||
)
|
||||
|
||||
@@ -47,17 +47,11 @@
|
||||
#include <string.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/printload.h>
|
||||
#include <px4_platform/cpuload.h>
|
||||
#include <px4_platform_common/printload.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
/**
|
||||
* Start the top application.
|
||||
*/
|
||||
__EXPORT int top_main(int argc, char *argv[]);
|
||||
|
||||
|
||||
static void print_usage(void)
|
||||
{
|
||||
PRINT_MODULE_DESCRIPTION("Monitor running processes and their CPU, stack usage, priority and state");
|
||||
@@ -66,32 +60,30 @@ static void print_usage(void)
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("once", "print load only once");
|
||||
}
|
||||
|
||||
int
|
||||
top_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int top_main(int argc, char *argv[])
|
||||
{
|
||||
hrt_abstime curr_time = hrt_absolute_time();
|
||||
|
||||
struct print_load_s load;
|
||||
init_print_load_s(curr_time, &load);
|
||||
print_load_s load{};
|
||||
init_print_load(&load);
|
||||
px4_usleep(200000);
|
||||
|
||||
/* clear screen */
|
||||
dprintf(1, "\033[2J\n");
|
||||
|
||||
if (argc > 1) {
|
||||
if (!strcmp(argv[1], "once")) {
|
||||
print_load(curr_time, 1, &load);
|
||||
px4_sleep(1);
|
||||
print_load(hrt_absolute_time(), 1, &load);
|
||||
print_load(STDOUT_FILENO, &load);
|
||||
|
||||
} else {
|
||||
print_usage();
|
||||
}
|
||||
|
||||
cpuload_monitor_stop();
|
||||
return 0;
|
||||
}
|
||||
|
||||
for (;;) {
|
||||
print_load(curr_time, 1, &load);
|
||||
print_load(STDOUT_FILENO, &load);
|
||||
|
||||
/* Sleep 200 ms waiting for user input five times ~ 1s */
|
||||
for (int k = 0; k < 5; k++) {
|
||||
@@ -108,6 +100,7 @@ top_main(int argc, char *argv[])
|
||||
ret = read(0, &c, 1);
|
||||
|
||||
if (ret) {
|
||||
cpuload_monitor_stop();
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -116,6 +109,7 @@ top_main(int argc, char *argv[])
|
||||
case 0x1b: // esc
|
||||
case 'c':
|
||||
case 'q':
|
||||
cpuload_monitor_stop();
|
||||
return 0;
|
||||
/* not reached */
|
||||
}
|
||||
@@ -123,9 +117,8 @@ top_main(int argc, char *argv[])
|
||||
|
||||
px4_usleep(200000);
|
||||
}
|
||||
|
||||
curr_time = hrt_absolute_time();
|
||||
}
|
||||
|
||||
cpuload_monitor_stop();
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user