From 28096fa0638750b5208e286e70e0dc5b0b55b8e9 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 14 Jul 2020 17:38:32 -0400 Subject: [PATCH 1/4] load_mon updates - increase rate - cpu load calculation grab timestamp atomically - only check one task per cycle (but cycle at a higher rate) - decrease available FD threshold - minor cleanup --- src/modules/load_mon/CMakeLists.txt | 2 +- src/modules/load_mon/load_mon.cpp | 190 +++++++++++----------------- src/modules/load_mon/params.c | 2 +- 3 files changed, 74 insertions(+), 120 deletions(-) diff --git a/src/modules/load_mon/CMakeLists.txt b/src/modules/load_mon/CMakeLists.txt index d98108ca2dc9..7f1f59c837c8 100644 --- a/src/modules/load_mon/CMakeLists.txt +++ b/src/modules/load_mon/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# Copyright (c) 2016-2020 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 diff --git a/src/modules/load_mon/load_mon.cpp b/src/modules/load_mon/load_mon.cpp index 1ababd4a682b..f746eb6974e6 100644 --- a/src/modules/load_mon/load_mon.cpp +++ b/src/modules/load_mon/load_mon.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-2020 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 @@ -62,16 +62,13 @@ static constexpr unsigned STACK_LOW_WARNING_THRESHOLD = 100; static constexpr unsigned STACK_LOW_WARNING_THRESHOLD = 300; #endif -#define FDS_LOW_WARNING_THRESHOLD 3 ///< if free file descriptors fall below this, print a warning +static constexpr unsigned FDS_LOW_WARNING_THRESHOLD = 2; ///< if free file descriptors fall below this, print a warning + +using namespace time_literals; namespace load_mon { -extern "C" __EXPORT int load_mon_main(int argc, char *argv[]); - -// Run it at 1 Hz. -const unsigned LOAD_MON_INTERVAL_US = 1000000; - class LoadMon : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: @@ -96,18 +93,13 @@ class LoadMon : public ModuleBase, public ModuleParams, public px4::Sch void Run() override; /** Do a calculation of the CPU load and publish it. */ - void _cpuload(); - - /** Calculate the memory usage */ - float _ram_used(); + void cpuload(); -#ifdef __PX4_NUTTX /* Calculate stack usage */ - void _stack_usage(); + void stack_usage(); int _stack_task_index{0}; uORB::PublicationQueued _task_stack_info_pub{ORB_ID(task_stack_info)}; -#endif DEFINE_PARAMETERS( (ParamBool) _param_sys_stck_en @@ -118,13 +110,12 @@ class LoadMon : public ModuleBase, public ModuleParams, public px4::Sch hrt_abstime _last_idle_time{0}; hrt_abstime _last_idle_time_sample{0}; - perf_counter_t _stack_perf; + perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; }; LoadMon::LoadMon() : ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default), - _stack_perf(perf_alloc(PC_ELAPSED, "stack_check")) + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) { } @@ -132,7 +123,7 @@ LoadMon::~LoadMon() { ScheduleClear(); - perf_free(_stack_perf); + perf_free(_cycle_perf); } int LoadMon::task_spawn(int argc, char *argv[]) @@ -153,161 +144,125 @@ int LoadMon::task_spawn(int argc, char *argv[]) return 0; } -void -LoadMon::start() +void LoadMon::start() { - ScheduleOnInterval(LOAD_MON_INTERVAL_US); + ScheduleOnInterval(300_ms); } void LoadMon::Run() { - _cpuload(); + perf_begin(_cycle_perf); -#ifdef __PX4_NUTTX + cpuload(); if (_param_sys_stck_en.get()) { - _stack_usage(); + stack_usage(); } -#endif - if (should_exit()) { ScheduleClear(); exit_and_cleanup(); } + + perf_end(_cycle_perf); } -void LoadMon::_cpuload() +void LoadMon::cpuload() { if (_last_idle_time == 0) { - /* Just get the time in the first iteration */ + // Just get the time in the first iteration */ _last_idle_time = system_load.tasks[0].total_runtime; + _last_idle_time_sample = hrt_absolute_time(); return; } - /* compute system load */ + irqstate_t irqstate = enter_critical_section(); + const hrt_abstime now = hrt_absolute_time(); const hrt_abstime total_runtime = system_load.tasks[0].total_runtime; - const hrt_abstime interval = hrt_elapsed_time(&_last_idle_time_sample); - const hrt_abstime interval_idletime = total_runtime - _last_idle_time; + leave_critical_section(irqstate); - _last_idle_time = total_runtime; - _last_idle_time_sample = hrt_absolute_time(); + // compute system load + const float interval = now - _last_idle_time_sample; + const float interval_idletime = total_runtime - _last_idle_time; + + // get ram usage + struct mallinfo mem = mallinfo(); + float ram_usage = (float)mem.uordblks / mem.arena; cpuload_s cpuload{}; - cpuload.load = 1.0f - (float)interval_idletime / (float)interval; - cpuload.ram_usage = _ram_used(); + cpuload.load = 1.f - interval_idletime / interval; + cpuload.ram_usage = ram_usage; cpuload.timestamp = hrt_absolute_time(); _cpuload_pub.publish(cpuload); -} - -float LoadMon::_ram_used() -{ -#ifdef __PX4_NUTTX - struct mallinfo mem; - -#ifdef CONFIG_CAN_PASS_STRUCTS - mem = mallinfo(); -#else - (void)mallinfo(&mem); -#endif /* CONFIG_CAN_PASS_STRUCTS */ - - // mem.arena: total ram (bytes) - // mem.uordblks: used (bytes) - // mem.fordblks: free (bytes) - // mem.mxordblk: largest remaining block (bytes) - return (float)mem.uordblks / mem.arena; - -#else - return 0.0f; -#endif + // store for next iteration + _last_idle_time = total_runtime; + _last_idle_time_sample = now; } -#ifdef __PX4_NUTTX -void LoadMon::_stack_usage() +void LoadMon::stack_usage() { - int task_index = 0; + unsigned stack_free = 0; + unsigned fds_free = FDS_LOW_WARNING_THRESHOLD + 1; - /* Scan maximum num_tasks_per_cycle tasks to reduce load. */ - const int num_tasks_per_cycle = 2; + bool checked_task = false; - for (int i = _stack_task_index; i < _stack_task_index + num_tasks_per_cycle; i++) { - task_index = i % CONFIG_MAX_TASKS; - unsigned stack_free = 0; - unsigned fds_free = FDS_LOW_WARNING_THRESHOLD + 1; - bool checked_task = false; + task_stack_info_s task_stack_info{}; + static_assert(sizeof(task_stack_info.task_name) == CONFIG_TASK_NAME_SIZE, + "task_stack_info.task_name must match NuttX CONFIG_TASK_NAME_SIZE"); - perf_begin(_stack_perf); - sched_lock(); + sched_lock(); - task_stack_info_s task_stack_info = {}; + if (system_load.tasks[_stack_task_index].valid && (system_load.tasks[_stack_task_index].tcb->pid > 0)) { - if (system_load.tasks[task_index].valid && (system_load.tasks[task_index].tcb->pid > 0)) { + stack_free = up_check_tcbstack_remain(system_load.tasks[_stack_task_index].tcb); - stack_free = up_check_tcbstack_remain(system_load.tasks[task_index].tcb); + strncpy((char *)task_stack_info.task_name, system_load.tasks[_stack_task_index].tcb->name, CONFIG_TASK_NAME_SIZE - 1); + task_stack_info.task_name[CONFIG_TASK_NAME_SIZE - 1] = '\0'; - static_assert(sizeof(task_stack_info.task_name) == CONFIG_TASK_NAME_SIZE, - "task_stack_info.task_name must match NuttX CONFIG_TASK_NAME_SIZE"); - strncpy((char *)task_stack_info.task_name, system_load.tasks[task_index].tcb->name, CONFIG_TASK_NAME_SIZE - 1); - task_stack_info.task_name[CONFIG_TASK_NAME_SIZE - 1] = '\0'; + checked_task = true; #if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = system_load.tasks[task_index].tcb->group; + FAR struct task_group_s *group = system_load.tasks[_stack_task_index].tcb->group; - unsigned tcb_num_used_fds = 0; + unsigned tcb_num_used_fds = 0; - 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; - } + 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; } - - fds_free = CONFIG_NFILE_DESCRIPTORS - tcb_num_used_fds; } -#endif // CONFIG_NFILE_DESCRIPTORS - - checked_task = true; + fds_free = CONFIG_NFILE_DESCRIPTORS - tcb_num_used_fds; } - sched_unlock(); - perf_end(_stack_perf); - - if (checked_task) { +#endif // CONFIG_NFILE_DESCRIPTORS + } - task_stack_info.stack_free = stack_free; - task_stack_info.timestamp = hrt_absolute_time(); + sched_unlock(); - _task_stack_info_pub.publish(task_stack_info); + if (checked_task) { + task_stack_info.stack_free = stack_free; + task_stack_info.timestamp = hrt_absolute_time(); - /* - * Found task low on stack, report and exit. Continue here in next cycle. - */ - if (stack_free < STACK_LOW_WARNING_THRESHOLD) { - PX4_WARN("%s low on stack! (%i bytes left)", task_stack_info.task_name, stack_free); - break; - } + _task_stack_info_pub.publish(task_stack_info); - /* - * Found task low on file descriptors, report and exit. Continue here in next cycle. - */ - if (fds_free < FDS_LOW_WARNING_THRESHOLD) { - PX4_WARN("%s low on FDs! (%i FDs left)", task_stack_info.task_name, fds_free); - break; - } + // Found task low on stack, report and exit. Continue here in next cycle. + if (stack_free < STACK_LOW_WARNING_THRESHOLD) { + PX4_WARN("%s low on stack! (%i bytes left)", task_stack_info.task_name, stack_free); + } - } else { - /* No task here, check one more task in same cycle. */ - _stack_task_index++; + // Found task low on file descriptors, report and exit. Continue here in next cycle. + if (fds_free < FDS_LOW_WARNING_THRESHOLD) { + PX4_WARN("%s low on FDs! (%i FDs left)", task_stack_info.task_name, fds_free); } } - /* Continue after last checked task next cycle. */ - _stack_task_index = task_index + 1; + // Continue after last checked task next cycle + _stack_task_index = (_stack_task_index + 1) % CONFIG_MAX_TASKS; } -#endif int LoadMon::print_usage(const char *reason) { @@ -318,7 +273,7 @@ int LoadMon::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -Background process running periodically with 1 Hz on the LP work queue to calculate the CPU load and RAM +Background process running periodically with 1 Hz on the low priority work queue to calculate the CPU load and RAM usage and publish the `cpuload` topic. On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, @@ -331,8 +286,7 @@ which will also appear in the log file. return 0; } - -int load_mon_main(int argc, char *argv[]) +extern "C" __EXPORT int load_mon_main(int argc, char *argv[]) { return LoadMon::main(argc, argv); } diff --git a/src/modules/load_mon/params.c b/src/modules/load_mon/params.c index 40ac82fa55eb..c2292d996b7b 100644 --- a/src/modules/load_mon/params.c +++ b/src/modules/load_mon/params.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013-2017 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2020 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 From 0f62d4f240c4151e46ccc1ad683d9b01c2386edb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 15 Jul 2020 11:44:08 -0400 Subject: [PATCH 2/4] load_mon: split out header --- src/modules/load_mon/CMakeLists.txt | 6 +- .../load_mon/{load_mon.cpp => LoadMon.cpp} | 69 +------------- src/modules/load_mon/LoadMon.hpp | 95 +++++++++++++++++++ 3 files changed, 99 insertions(+), 71 deletions(-) rename src/modules/load_mon/{load_mon.cpp => LoadMon.cpp} (78%) create mode 100644 src/modules/load_mon/LoadMon.hpp diff --git a/src/modules/load_mon/CMakeLists.txt b/src/modules/load_mon/CMakeLists.txt index 7f1f59c837c8..a2c6ee06471f 100644 --- a/src/modules/load_mon/CMakeLists.txt +++ b/src/modules/load_mon/CMakeLists.txt @@ -35,8 +35,8 @@ px4_add_module( MAIN load_mon COMPILE_FLAGS SRCS - load_mon.cpp + LoadMon.cpp + LoadMon.hpp DEPENDS px4_work_queue - ) - +) diff --git a/src/modules/load_mon/load_mon.cpp b/src/modules/load_mon/LoadMon.cpp similarity index 78% rename from src/modules/load_mon/load_mon.cpp rename to src/modules/load_mon/LoadMon.cpp index f746eb6974e6..48fe546e2bd4 100644 --- a/src/modules/load_mon/load_mon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -31,29 +31,7 @@ * ****************************************************************************/ -/** - * @file load_mon.cpp - * - * @author Jonathan Challinger - * @author Julian Oes - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(__PX4_NUTTX) && !defined(CONFIG_SCHED_INSTRUMENTATION) -# error load_mon support requires CONFIG_SCHED_INSTRUMENTATION -#endif +#include "LoadMon.hpp" // if free stack space falls below this, print a warning #if defined(CONFIG_ARMV7M_STACKCHECK) @@ -69,50 +47,6 @@ using namespace time_literals; namespace load_mon { -class LoadMon : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem -{ -public: - LoadMon(); - ~LoadMon() override; - - static int task_spawn(int argc, char *argv[]); - - /** @see ModuleBase */ - static int custom_command(int argc, char *argv[]) - { - return print_usage("unknown command"); - } - - /** @see ModuleBase */ - static int print_usage(const char *reason = nullptr); - - void start(); - -private: - /** Do a compute and schedule the next cycle. */ - void Run() override; - - /** Do a calculation of the CPU load and publish it. */ - void cpuload(); - - /* Calculate stack usage */ - void stack_usage(); - - int _stack_task_index{0}; - uORB::PublicationQueued _task_stack_info_pub{ORB_ID(task_stack_info)}; - - DEFINE_PARAMETERS( - (ParamBool) _param_sys_stck_en - ) - - uORB::Publication _cpuload_pub{ORB_ID(cpuload)}; - - hrt_abstime _last_idle_time{0}; - hrt_abstime _last_idle_time_sample{0}; - - perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; -}; - LoadMon::LoadMon() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) @@ -122,7 +56,6 @@ LoadMon::LoadMon() : LoadMon::~LoadMon() { ScheduleClear(); - perf_free(_cycle_perf); } diff --git a/src/modules/load_mon/LoadMon.hpp b/src/modules/load_mon/LoadMon.hpp new file mode 100644 index 000000000000..b426461f9f50 --- /dev/null +++ b/src/modules/load_mon/LoadMon.hpp @@ -0,0 +1,95 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2020 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 + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace load_mon +{ + +class LoadMon : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + LoadMon(); + ~LoadMon() override; + + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]) + { + return print_usage("unknown command"); + } + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + void start(); + +private: + /** Do a compute and schedule the next cycle. */ + void Run() override; + + /** Do a calculation of the CPU load and publish it. */ + void cpuload(); + + /* Calculate stack usage */ + void stack_usage(); + + int _stack_task_index{0}; + + uORB::PublicationQueued _task_stack_info_pub{ORB_ID(task_stack_info)}; + uORB::Publication _cpuload_pub{ORB_ID(cpuload)}; + + hrt_abstime _last_idle_time{0}; + hrt_abstime _last_idle_time_sample{0}; + + perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; + + DEFINE_PARAMETERS( + (ParamBool) _param_sys_stck_en + ) +}; + +} // namespace load_mon From cb366dc98162485cb087e5a842604d18d3d22d30 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 15 Jul 2020 12:18:02 -0400 Subject: [PATCH 3/4] Jenkins: hardware print cpuload --- .ci/Jenkinsfile-hardware | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.ci/Jenkinsfile-hardware b/.ci/Jenkinsfile-hardware index 093d31883ad0..6592427c0f5d 100644 --- a/.ci/Jenkinsfile-hardware +++ b/.ci/Jenkinsfile-hardware @@ -922,6 +922,7 @@ void statusFTDI() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "gps status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener adc_report"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener battery_status"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener cpuload"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener logger_status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_fifo"' @@ -985,6 +986,7 @@ void statusSEGGER() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "gps status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener adc_report"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener battery_status"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener cpuload"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener logger_status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_fifo"' From 7c5a53a1887d5bfc713b81ee4d47b6eaa1796549 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 16 Jul 2020 09:47:26 -0400 Subject: [PATCH 4/4] load_mon: remove obsolete rate comment in description --- src/modules/load_mon/LoadMon.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index 48fe546e2bd4..6d69bdfecaad 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -206,7 +206,7 @@ int LoadMon::print_usage(const char *reason) PRINT_MODULE_DESCRIPTION( R"DESCR_STR( ### Description -Background process running periodically with 1 Hz on the low priority work queue to calculate the CPU load and RAM +Background process running periodically on the low priority work queue to calculate the CPU load and RAM usage and publish the `cpuload` topic. On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output,