-
Notifications
You must be signed in to change notification settings - Fork 13.5k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
load_mon: increase cpuload update rate, get corresponding time safetly, and misc cleanup #15342
Merged
Merged
Changes from all commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,227 @@ | ||
/**************************************************************************** | ||
* | ||
* 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. | ||
* | ||
****************************************************************************/ | ||
|
||
#include "LoadMon.hpp" | ||
|
||
// if free stack space falls below this, print a warning | ||
#if defined(CONFIG_ARMV7M_STACKCHECK) | ||
static constexpr unsigned STACK_LOW_WARNING_THRESHOLD = 100; | ||
#else | ||
static constexpr unsigned STACK_LOW_WARNING_THRESHOLD = 300; | ||
#endif | ||
|
||
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 | ||
{ | ||
|
||
LoadMon::LoadMon() : | ||
ModuleParams(nullptr), | ||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) | ||
{ | ||
} | ||
|
||
LoadMon::~LoadMon() | ||
{ | ||
ScheduleClear(); | ||
perf_free(_cycle_perf); | ||
} | ||
|
||
int LoadMon::task_spawn(int argc, char *argv[]) | ||
{ | ||
LoadMon *obj = new LoadMon(); | ||
|
||
if (!obj) { | ||
PX4_ERR("alloc failed"); | ||
return -1; | ||
} | ||
|
||
_object.store(obj); | ||
_task_id = task_id_is_work_queue; | ||
|
||
/* Schedule a cycle to start things. */ | ||
obj->start(); | ||
|
||
return 0; | ||
} | ||
|
||
void LoadMon::start() | ||
{ | ||
ScheduleOnInterval(300_ms); | ||
} | ||
|
||
void LoadMon::Run() | ||
{ | ||
perf_begin(_cycle_perf); | ||
|
||
cpuload(); | ||
|
||
if (_param_sys_stck_en.get()) { | ||
stack_usage(); | ||
} | ||
|
||
if (should_exit()) { | ||
ScheduleClear(); | ||
exit_and_cleanup(); | ||
} | ||
|
||
perf_end(_cycle_perf); | ||
} | ||
|
||
void LoadMon::cpuload() | ||
{ | ||
if (_last_idle_time == 0) { | ||
// 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; | ||
} | ||
|
||
irqstate_t irqstate = enter_critical_section(); | ||
const hrt_abstime now = hrt_absolute_time(); | ||
const hrt_abstime total_runtime = system_load.tasks[0].total_runtime; | ||
leave_critical_section(irqstate); | ||
|
||
// 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.f - interval_idletime / interval; | ||
cpuload.ram_usage = ram_usage; | ||
cpuload.timestamp = hrt_absolute_time(); | ||
|
||
_cpuload_pub.publish(cpuload); | ||
|
||
// store for next iteration | ||
_last_idle_time = total_runtime; | ||
_last_idle_time_sample = now; | ||
} | ||
|
||
void LoadMon::stack_usage() | ||
{ | ||
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"); | ||
|
||
sched_lock(); | ||
|
||
if (system_load.tasks[_stack_task_index].valid && (system_load.tasks[_stack_task_index].tcb->pid > 0)) { | ||
|
||
stack_free = up_check_tcbstack_remain(system_load.tasks[_stack_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'; | ||
|
||
checked_task = true; | ||
|
||
#if CONFIG_NFILE_DESCRIPTORS > 0 | ||
FAR struct task_group_s *group = system_load.tasks[_stack_task_index].tcb->group; | ||
|
||
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; | ||
} | ||
} | ||
|
||
fds_free = CONFIG_NFILE_DESCRIPTORS - tcb_num_used_fds; | ||
} | ||
|
||
#endif // CONFIG_NFILE_DESCRIPTORS | ||
} | ||
|
||
sched_unlock(); | ||
|
||
if (checked_task) { | ||
task_stack_info.stack_free = stack_free; | ||
task_stack_info.timestamp = hrt_absolute_time(); | ||
|
||
_task_stack_info_pub.publish(task_stack_info); | ||
|
||
// 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); | ||
} | ||
|
||
// 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 = (_stack_task_index + 1) % CONFIG_MAX_TASKS; | ||
} | ||
|
||
int LoadMon::print_usage(const char *reason) | ||
{ | ||
if (reason) { | ||
PX4_ERR("%s\n", reason); | ||
} | ||
|
||
PRINT_MODULE_DESCRIPTION( | ||
R"DESCR_STR( | ||
### Description | ||
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, | ||
which will also appear in the log file. | ||
)DESCR_STR"); | ||
|
||
PRINT_MODULE_USAGE_NAME("load_mon", "system"); | ||
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); | ||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); | ||
return 0; | ||
} | ||
|
||
extern "C" __EXPORT int load_mon_main(int argc, char *argv[]) | ||
{ | ||
return LoadMon::main(argc, argv); | ||
} | ||
|
||
} // namespace load_mon |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 <drivers/drv_hrt.h> | ||
#include <lib/perf/perf_counter.h> | ||
#include <px4_platform_common/px4_config.h> | ||
#include <px4_platform_common/defines.h> | ||
#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 <uORB/Publication.hpp> | ||
#include <uORB/topics/cpuload.h> | ||
#include <uORB/topics/task_stack_info.h> | ||
|
||
namespace load_mon | ||
{ | ||
|
||
class LoadMon : public ModuleBase<LoadMon>, 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_s> _task_stack_info_pub{ORB_ID(task_stack_info)}; | ||
uORB::Publication<cpuload_s> _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<px4::params::SYS_STCK_EN>) _param_sys_stck_en | ||
) | ||
}; | ||
|
||
} // namespace load_mon |
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
These warnings will now appear 3 times per second and spam the log quite a bit, right?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Only in the worst case if running the max number of tasks (32 or 64) and every one of them was either low on stack or FDs.
Overall it's kind of a lateral move. Currently in master it cycles at 1 Hz, but each iteration checks 2 tasks, and if a task entry (an array of CONFIG_MAX_TASKS) is empty it jumps forward. Now it runs slightly faster for the sake of cpuload measurement, but it's doing less work per iteration checking tasks.