From 8cda0ec26669302b2e06513b9595b7a78c2257db Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 27 Jul 2015 17:07:13 +0200 Subject: [PATCH 1/7] EKF memory usage fix --- .../ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 2 +- src/modules/ekf_att_pos_estimator/module.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 07b8c8dfd5..4588f3c901 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -1115,7 +1115,7 @@ int AttitudePositionEstimatorEKF::start() _estimator_task = task_spawn_cmd("ekf_att_pos_estimator", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 7500, + 4800, (main_t)&AttitudePositionEstimatorEKF::task_main_trampoline, nullptr); diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk index f519621137..2a582ebbb8 100644 --- a/src/modules/ekf_att_pos_estimator/module.mk +++ b/src/modules/ekf_att_pos_estimator/module.mk @@ -42,5 +42,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \ estimator_22states.cpp \ estimator_utilities.cpp -EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=6100 +EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=3400 From 7cb97f1d39e3e50f3d2673dc2641a6c206938aa2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 14:20:21 +0200 Subject: [PATCH 2/7] top: Fix code style --- src/systemcmds/top/top.c | 123 +++++++++++++++++++++++---------------- 1 file changed, 73 insertions(+), 50 deletions(-) diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index 37e913040d..f82b4bda58 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2012, 2013, 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 @@ -36,8 +35,8 @@ * @file top.c * Tool similar to UNIX top command * @see http://en.wikipedia.org/wiki/Top_unix - * - * @author Lorenz Meier + * + * @author Lorenz Meier */ #include @@ -64,23 +63,40 @@ static const char * tstate_name(const tstate_t s) { switch (s) { - case TSTATE_TASK_INVALID: return "init"; + 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_PENDING: + return "PEND"; - case TSTATE_TASK_INACTIVE: return "inact"; - case TSTATE_WAIT_SEM: return "w:sem"; + 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"; + + 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"; + + 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"; + + case TSTATE_WAIT_PAGEFILL: + return "w:pgf"; #endif default: @@ -102,8 +118,9 @@ top_main(void) uint64_t last_times[CONFIG_MAX_TASKS]; float curr_loads[CONFIG_MAX_TASKS]; - for (int t = 0; t < CONFIG_MAX_TASKS; t++) + for (int t = 0; t < CONFIG_MAX_TASKS; t++) { last_times[t] = 0; + } float interval_time_ms_inv = 0.f; @@ -118,8 +135,9 @@ top_main(void) curr_time_us = hrt_absolute_time(); idle_time_us = system_load.tasks[0].total_runtime; - if (new_time > interval_start_time) + if (new_time > interval_start_time) { interval_time_ms_inv = 1.f / ((float)((new_time - interval_start_time) / 1000)); + } running_count = 0; blocked_count = 0; @@ -155,19 +173,22 @@ top_main(void) } interval_runtime = (system_load.tasks[i].valid && last_times[i] > 0 && - system_load.tasks[i].total_runtime > last_times[i]) - ? (system_load.tasks[i].total_runtime - last_times[i]) / 1000 - : 0; + system_load.tasks[i].total_runtime > last_times[i]) + ? (system_load.tasks[i].total_runtime - last_times[i]) / 1000 + : 0; last_times[i] = system_load.tasks[i].total_runtime; if (system_load.tasks[i].valid && (new_time > interval_start_time)) { curr_loads[i] = interval_runtime * interval_time_ms_inv; - if (i > 0) + if (i > 0) { total_user_time += interval_runtime; - } else + } + + } else { curr_loads[i] = 0; + } } for (i = 0; i < CONFIG_MAX_TASKS; i++) { @@ -182,63 +203,65 @@ top_main(void) /* this can happen if one tasks total runtime was not computed correctly by the scheduler instrumentation TODO */ - if (task_load > (1.f - idle)) + if (task_load > (1.f - idle)) { task_load = (1.f - idle); + } sched_load = 1.f - idle - task_load; /* print system information */ printf("\033[H"); /* move cursor home and clear screen */ printf(CL "Processes: %d total, %d running, %d sleeping\n", - system_load.total_count, - running_count, - blocked_count); + system_load.total_count, + running_count, + blocked_count); printf(CL "CPU usage: %.2f%% tasks, %.2f%% sched, %.2f%% idle\n", - (double)(task_load * 100.f), - (double)(sched_load * 100.f), - (double)(idle * 100.f)); + (double)(task_load * 100.f), + (double)(sched_load * 100.f), + (double)(idle * 100.f)); printf(CL "Uptime: %.3fs total, %.3fs idle\n\n", - (double)curr_time_us / 1000000.d, - (double)idle_time_us / 1000000.d); + (double)curr_time_us / 1000000.d, + (double)idle_time_us / 1000000.d); /* header for task list */ printf(CL "%4s %*-s %8s %6s %11s %10s %-6s\n", - "PID", - CONFIG_TASK_NAME_SIZE, "COMMAND", - "CPU(ms)", - "CPU(%)", - "USED/STACK", - "PRIO(BASE)", + "PID", + CONFIG_TASK_NAME_SIZE, "COMMAND", + "CPU(ms)", + "CPU(%)", + "USED/STACK", + "PRIO(BASE)", #if CONFIG_RR_INTERVAL > 0 - "TSLICE" + "TSLICE" #else - "STATE" + "STATE" #endif - ); + ); } unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr - - (uintptr_t)system_load.tasks[i].tcb->stack_alloc_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) + if (*stack_sweeper++ != 0xff) { break; + } stack_free++; } printf(CL "%4d %*-s %8lld %2d.%03d %5u/%5u %3u (%3u) ", - system_load.tasks[i].tcb->pid, - CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, - (system_load.tasks[i].total_runtime / 1000), - (int)(curr_loads[i] * 100.0f), - (int)((curr_loads[i] * 100.0f - (int)(curr_loads[i] * 100.0f)) * 1000), - stack_size - stack_free, - stack_size, - system_load.tasks[i].tcb->sched_priority, - system_load.tasks[i].tcb->base_priority); + system_load.tasks[i].tcb->pid, + CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, + (system_load.tasks[i].total_runtime / 1000), + (int)(curr_loads[i] * 100.0f), + (int)((curr_loads[i] * 100.0f - (int)(curr_loads[i] * 100.0f)) * 1000), + stack_size - stack_free, + stack_size, + system_load.tasks[i].tcb->sched_priority, + system_load.tasks[i].tcb->base_priority); #if CONFIG_RR_INTERVAL > 0 /* print scheduling info with RR time slice */ From b70c9a84c621af6d0a48c0f1ba99e9385426e4ff Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 15:22:28 +0200 Subject: [PATCH 3/7] systemlib: Add ability to dump memory usage --- src/modules/systemlib/module.mk | 1 + src/modules/systemlib/printload.c | 278 ++++++++++++++++++++++++++++++ src/modules/systemlib/printload.h | 59 +++++++ src/systemcmds/top/top.c | 230 ++---------------------- 4 files changed, 354 insertions(+), 214 deletions(-) create mode 100644 src/modules/systemlib/printload.c create mode 100644 src/modules/systemlib/printload.h diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index f2499bbb13..b531330ab3 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -42,6 +42,7 @@ SRCS = err.c \ bson/tinybson.c \ conversions.c \ cpuload.c \ + printload.c \ getopt_long.c \ up_cxxinitialize.c \ pid/pid.c \ diff --git a/src/modules/systemlib/printload.c b/src/modules/systemlib/printload.c new file mode 100644 index 0000000000..e40791fe89 --- /dev/null +++ b/src/modules/systemlib/printload.c @@ -0,0 +1,278 @@ +/**************************************************************************** + * + * 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 + */ + +#include +#include + +#include +#include +#include + +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(uint64_t t, int fd, struct print_load_s *print_state) +{ + print_state->new_time = t; + + int i; + uint64_t curr_time_us; + uint64_t idle_time_us; + char *clear_line = '\0'; + + /* print system information */ + if (fd == 1) { + dprintf(fd, "\033[H"); /* move cursor home and clear screen */ + clear_line = CL; + } + + 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)); + } + + print_state->running_count = 0; + print_state->blocked_count = 0; + print_state->total_user_time = 0; + + for (i = 0; i < CONFIG_MAX_TASKS; i++) { + uint64_t interval_runtime; + + if (system_load.tasks[i].valid) { + switch (system_load.tasks[i].tcb->task_state) { + case TSTATE_TASK_PENDING: + case TSTATE_TASK_READYTORUN: + case TSTATE_TASK_RUNNING: + print_state->running_count++; + break; + + case TSTATE_TASK_INVALID: + case TSTATE_TASK_INACTIVE: + case TSTATE_WAIT_SEM: +#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 + print_state->blocked_count++; + break; + } + } + + interval_runtime = (system_load.tasks[i].valid && print_state->last_times[i] > 0 && + system_load.tasks[i].total_runtime > print_state->last_times[i]) + ? (system_load.tasks[i].total_runtime - print_state->last_times[i]) / 1000 + : 0; + + print_state->last_times[i] = system_load.tasks[i].total_runtime; + + if (system_load.tasks[i].valid && (print_state->new_time > print_state->interval_start_time)) { + print_state->curr_loads[i] = interval_runtime * print_state->interval_time_ms_inv; + + if (i > 0) { + print_state->total_user_time += interval_runtime; + } + + } else { + print_state->curr_loads[i] = 0; + } + } + + for (i = 0; i < CONFIG_MAX_TASKS; i++) { + if (system_load.tasks[i].valid && (print_state->new_time > print_state->interval_start_time)) { + if (system_load.tasks[i].tcb->pid == 0) { + float idle; + float task_load; + float sched_load; + + idle = print_state->curr_loads[0]; + 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)) { + task_load = (1.f - idle); + } + + sched_load = 1.f - idle - task_load; + + dprintf(fd, "%sProcesses: %d total, %d running, %d sleeping\n", + clear_line, + system_load.total_count, + print_state->running_count, + print_state->blocked_count); + dprintf(fd, "%sCPU usage: %.2f%% tasks, %.2f%% sched, %.2f%% idle\n", + clear_line, + (double)(task_load * 100.f), + (double)(sched_load * 100.f), + (double)(idle * 100.f)); + dprintf(fd, "%sUptime: %.3fs total, %.3fs idle\n%s\n", + clear_line, + (double)curr_time_us / 1000000.d, + (double)idle_time_us / 1000000.d, + clear_line); + + /* header for task list */ + dprintf(fd, "%s%4s %*-s %8s %6s %11s %10s %-6s\n", + clear_line, + "PID", + CONFIG_TASK_NAME_SIZE, "COMMAND", + "CPU(ms)", + "CPU(%)", + "USED/STACK", + "PRIO(BASE)", +#if CONFIG_RR_INTERVAL > 0 + "TSLICE" +#else + "STATE" +#endif + ); + } + + 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++; + } + + dprintf(fd, "%s%4d %*-s %8lld %2d.%03d %5u/%5u %3u (%3u) ", + clear_line, + system_load.tasks[i].tcb->pid, + CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, + (system_load.tasks[i].total_runtime / 1000), + (int)(print_state->curr_loads[i] * 100.0f), + (int)((print_state->curr_loads[i] * 100.0f - (int)(print_state->curr_loads[i] * 100.0f)) * 1000), + stack_size - stack_free, + stack_size, + system_load.tasks[i].tcb->sched_priority, + system_load.tasks[i].tcb->base_priority); + +#if CONFIG_RR_INTERVAL > 0 + /* print scheduling info with RR time slice */ + dprintf(fd, " %6d\n", system_load.tasks[i].tcb->timeslice); +#else + // print task state instead + dprintf(fd, " %-6s\n", tstate_name(system_load.tasks[i].tcb->task_state)); +#endif + } + } + + print_state->interval_start_time = print_state->new_time; +} + diff --git a/src/modules/systemlib/printload.h b/src/modules/systemlib/printload.h new file mode 100644 index 0000000000..f0719d2106 --- /dev/null +++ b/src/modules/systemlib/printload.h @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * 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 + */ + +#include + +__EXPORT struct print_load_s { + uint64_t total_user_time; + + int running_count; + int blocked_count; + + uint64_t new_time; + uint64_t interval_start_time; + uint64_t last_times[CONFIG_MAX_TASKS]; + float curr_loads[CONFIG_MAX_TASKS]; + float interval_time_ms_inv; +}; + +__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); diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index f82b4bda58..a4846885c5 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -48,232 +48,34 @@ #include #include +#include #include -#define CL "\033[K" // clear line - /** * Start the top application. */ -__EXPORT int top_main(void); - -extern struct system_load_s system_load; - -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"; - } -} +__EXPORT int top_main(int argc, char *argv[]); int -top_main(void) +top_main(int argc, char *argv[]) { - uint64_t total_user_time = 0; + hrt_abstime curr_time = hrt_absolute_time(); - int running_count = 0; - int blocked_count = 0; - - uint64_t new_time = hrt_absolute_time(); - uint64_t interval_start_time = new_time; - - uint64_t last_times[CONFIG_MAX_TASKS]; - float curr_loads[CONFIG_MAX_TASKS]; - - for (int t = 0; t < CONFIG_MAX_TASKS; t++) { - last_times[t] = 0; - } - - float interval_time_ms_inv = 0.f; + struct print_load_s load; + init_print_load_s(curr_time, &load); /* clear screen */ - printf("\033[2J"); + dprintf(1, "\033[2J\n"); + + if (argc > 1 && !strcmp(argv[1], "once")) { + print_load(curr_time, 1, &load); + sleep(1); + print_load(hrt_absolute_time(), 1, &load); + return 0; + } for (;;) { - int i; - uint64_t curr_time_us; - uint64_t idle_time_us; - - curr_time_us = hrt_absolute_time(); - idle_time_us = system_load.tasks[0].total_runtime; - - if (new_time > interval_start_time) { - interval_time_ms_inv = 1.f / ((float)((new_time - interval_start_time) / 1000)); - } - - running_count = 0; - blocked_count = 0; - total_user_time = 0; - - for (i = 0; i < CONFIG_MAX_TASKS; i++) { - uint64_t interval_runtime; - - if (system_load.tasks[i].valid) { - switch (system_load.tasks[i].tcb->task_state) { - case TSTATE_TASK_PENDING: - case TSTATE_TASK_READYTORUN: - case TSTATE_TASK_RUNNING: - running_count++; - break; - - case TSTATE_TASK_INVALID: - case TSTATE_TASK_INACTIVE: - case TSTATE_WAIT_SEM: -#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 - blocked_count++; - break; - } - } - - interval_runtime = (system_load.tasks[i].valid && last_times[i] > 0 && - system_load.tasks[i].total_runtime > last_times[i]) - ? (system_load.tasks[i].total_runtime - last_times[i]) / 1000 - : 0; - - last_times[i] = system_load.tasks[i].total_runtime; - - if (system_load.tasks[i].valid && (new_time > interval_start_time)) { - curr_loads[i] = interval_runtime * interval_time_ms_inv; - - if (i > 0) { - total_user_time += interval_runtime; - } - - } else { - curr_loads[i] = 0; - } - } - - for (i = 0; i < CONFIG_MAX_TASKS; i++) { - if (system_load.tasks[i].valid && (new_time > interval_start_time)) { - if (system_load.tasks[i].tcb->pid == 0) { - float idle; - float task_load; - float sched_load; - - idle = curr_loads[0]; - task_load = (float)(total_user_time) * 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)) { - task_load = (1.f - idle); - } - - sched_load = 1.f - idle - task_load; - - /* print system information */ - printf("\033[H"); /* move cursor home and clear screen */ - printf(CL "Processes: %d total, %d running, %d sleeping\n", - system_load.total_count, - running_count, - blocked_count); - printf(CL "CPU usage: %.2f%% tasks, %.2f%% sched, %.2f%% idle\n", - (double)(task_load * 100.f), - (double)(sched_load * 100.f), - (double)(idle * 100.f)); - printf(CL "Uptime: %.3fs total, %.3fs idle\n\n", - (double)curr_time_us / 1000000.d, - (double)idle_time_us / 1000000.d); - - /* header for task list */ - printf(CL "%4s %*-s %8s %6s %11s %10s %-6s\n", - "PID", - CONFIG_TASK_NAME_SIZE, "COMMAND", - "CPU(ms)", - "CPU(%)", - "USED/STACK", - "PRIO(BASE)", -#if CONFIG_RR_INTERVAL > 0 - "TSLICE" -#else - "STATE" -#endif - ); - } - - 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++; - } - - printf(CL "%4d %*-s %8lld %2d.%03d %5u/%5u %3u (%3u) ", - system_load.tasks[i].tcb->pid, - CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, - (system_load.tasks[i].total_runtime / 1000), - (int)(curr_loads[i] * 100.0f), - (int)((curr_loads[i] * 100.0f - (int)(curr_loads[i] * 100.0f)) * 1000), - stack_size - stack_free, - stack_size, - system_load.tasks[i].tcb->sched_priority, - system_load.tasks[i].tcb->base_priority); - -#if CONFIG_RR_INTERVAL > 0 - /* print scheduling info with RR time slice */ - printf(" %6d\n", system_load.tasks[i].tcb->timeslice); -#else - // print task state instead - printf(" %-6s\n", tstate_name(system_load.tasks[i].tcb->task_state)); -#endif - } - } - - interval_start_time = new_time; + print_load(curr_time, 1, &load); /* Sleep 200 ms waiting for user input five times ~ 1s */ for (int k = 0; k < 5; k++) { @@ -302,7 +104,7 @@ top_main(void) usleep(200000); } - new_time = hrt_absolute_time(); + curr_time = hrt_absolute_time(); } return OK; From c264d6bb99792fe166bf045dc28a79890137d226 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 15:27:05 +0200 Subject: [PATCH 4/7] SDLOG2: Store load / mem use post-flight --- src/modules/sdlog2/sdlog2.c | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index c1c01ec06e..ea843f9202 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -105,6 +105,7 @@ #include #include #include +#include #include #include @@ -727,9 +728,16 @@ void sdlog2_start_log() } /* write all performance counters */ + hrt_abstime curr_time = hrt_absolute_time(); + struct print_load_s load; int perf_fd = open_perf_file("preflight"); + init_print_load_s(curr_time, &load); + print_load(curr_time, perf_fd, &load); dprintf(perf_fd, "PERFORMANCE COUNTERS PRE-FLIGHT\n\n"); perf_print_all(perf_fd); + dprintf(perf_fd, "\nLOAD PRE-FLIGHT\n\n"); + usleep(500 * 1000); + print_load(hrt_absolute_time(), perf_fd, &load); close(perf_fd); /* reset performance counters to get in-flight min and max values in post flight log */ @@ -765,8 +773,15 @@ void sdlog2_stop_log() /* write all performance counters */ int perf_fd = open_perf_file("postflight"); + hrt_abstime curr_time = hrt_absolute_time(); dprintf(perf_fd, "PERFORMANCE COUNTERS POST-FLIGHT\n\n"); perf_print_all(perf_fd); + struct print_load_s load; + dprintf(perf_fd, "\nLOAD POST-FLIGHT\n\n"); + init_print_load_s(curr_time, &load); + print_load(curr_time, perf_fd, &load); + sleep(1); + print_load(hrt_absolute_time(), perf_fd, &load); close(perf_fd); /* free log writer performance counter */ From 86e2e7e2a6d18403f063685d124880112f3e551a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 19:21:54 +0200 Subject: [PATCH 5/7] print load: Initialize to empty string, not null pointer --- src/modules/systemlib/printload.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/systemlib/printload.c b/src/modules/systemlib/printload.c index e40791fe89..23dde1ce44 100644 --- a/src/modules/systemlib/printload.c +++ b/src/modules/systemlib/printload.c @@ -120,7 +120,7 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state) int i; uint64_t curr_time_us; uint64_t idle_time_us; - char *clear_line = '\0'; + char *clear_line = ""; /* print system information */ if (fd == 1) { From e1aaaa1f1896fad5b422b0b8fe3c8c1edad7625c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 20:31:45 +0200 Subject: [PATCH 6/7] MAVLink: Start app using pre-configured streams to save some script execution overhead. Frees 1K during app startup, which should help FMUv1 considerably. --- ROMFS/px4fmu_common/init.d/rc.usb | 17 +---------------- src/modules/mavlink/mavlink_main.cpp | 24 ++++++++++++++++++++++-- src/modules/mavlink/mavlink_main.h | 3 ++- 3 files changed, 25 insertions(+), 19 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 027d2aca5d..4a157a683f 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -3,22 +3,7 @@ # USB MAVLink start # -mavlink start -r 800000 -d /dev/ttyACM0 -x -# Enable a number of interesting streams we want via USB -mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 300 -mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50 -mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10 -mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW_RAD -r 10 -mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20 -mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 100 -mavlink stream -d /dev/ttyACM0 -s ACTUATOR_CONTROL_TARGET0 -r 30 -mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5 -mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20 -mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10 -mavlink stream -d /dev/ttyACM0 -s LOCAL_POSITION_NED -r 30 -mavlink stream -d /dev/ttyACM0 -s MANUAL_CONTROL -r 5 -mavlink stream -d /dev/ttyACM0 -s HIGHRES_IMU -r 100 -mavlink stream -d /dev/ttyACM0 -s GPS_RAW_INT -r 20 +mavlink start -r 800000 -d /dev/ttyACM0 -m config -x # Exit shell to make it available to MAVLink exit diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f2dcd33d79..f172dfbeae 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1353,6 +1353,8 @@ Mavlink::task_main(int argc, char *argv[]) _mode = MAVLINK_MODE_ONBOARD; } else if (strcmp(optarg, "osd") == 0) { _mode = MAVLINK_MODE_OSD; + } else if (strcmp(optarg, "config") == 0) { + _mode = MAVLINK_MODE_CONFIG; } break; @@ -1449,8 +1451,6 @@ Mavlink::task_main(int argc, char *argv[]) /* start the MAVLink receiver */ _receive_thread = MavlinkReceiver::receive_start(this); - _task_running = true; - MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update)); uint64_t param_time = 0; MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status)); @@ -1537,6 +1537,23 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("RC_CHANNELS_RAW", 5.0f); break; + case MAVLINK_MODE_CONFIG: + // Enable a number of interesting streams we want via USB + configure_stream("PARAM_VALUE", 300.0f); + configure_stream("MISSION_ITEM", 50.0f); + configure_stream("NAMED_VALUE_FLOAT", 10.0f); + configure_stream("OPTICAL_FLOW_RAD", 10.0f); + configure_stream("VFR_HUD", 20.0f); + configure_stream("ATTITUDE", 100.0f); + configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f); + configure_stream("RC_CHANNELS_RAW", 5.0f); + configure_stream("SERVO_OUTPUT_RAW_0", 20.0f); + configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f); + configure_stream("LOCAL_POSITION_NED", 30.0f); + configure_stream("MANUAL_CONTROL", 5.0f); + configure_stream("HIGHRES_IMU", 100.0f); + configure_stream("GPS_RAW_INT", 20.0f); + default: break; } @@ -1703,6 +1720,9 @@ Mavlink::task_main(int argc, char *argv[]) } perf_end(_loop_perf); + + /* confirm task running only once fully initialized */ + _task_running = true; } delete _subscribe_to_stream; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index a484558579..455d9c796e 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -129,7 +129,8 @@ public: MAVLINK_MODE_NORMAL = 0, MAVLINK_MODE_CUSTOM, MAVLINK_MODE_ONBOARD, - MAVLINK_MODE_OSD + MAVLINK_MODE_OSD, + MAVLINK_MODE_CONFIG }; void set_mode(enum MAVLINK_MODE); From be638598936e7d0654a00384a53ac64c3654c685 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 22 Aug 2015 20:44:29 +0200 Subject: [PATCH 7/7] FMU driver: Remove excessive task space --- src/drivers/px4fmu/fmu.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index f2ec0285be..8109ec7603 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -355,7 +355,7 @@ PX4FMU::init() _task = task_spawn_cmd("fmuservo", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 1600, + 1200, (main_t)&PX4FMU::task_main_trampoline, nullptr);