Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
Firmware
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package Registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alberto Ruiz Garcia
Firmware
Commits
49be26b6
Unverified
Commit
49be26b6
authored
6 years ago
by
Daniel Agar
Committed by
GitHub
6 years ago
Browse files
Options
Downloads
Patches
Plain Diff
load_mon improve cpuload calculation and cleanup (#9852)
parent
63651da3
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/modules/load_mon/load_mon.cpp
+53
-70
53 additions, 70 deletions
src/modules/load_mon/load_mon.cpp
with
53 additions
and
70 deletions
src/modules/load_mon/load_mon.cpp
+
53
−
70
View file @
49be26b6
...
...
@@ -39,24 +39,17 @@
* @author Andreas Antener <andreas@uaventure.com>
*/
#include
<stdio.h>
#include
<stdlib.h>
#include
<string.h>
#include
<unistd.h>
#include
<drivers/drv_hrt.h>
#include
<lib/perf/perf_counter.h>
#include
<px4_config.h>
#include
<px4_defines.h>
#include
<px4_module.h>
#include
<px4_module_params.h>
#include
<px4_workqueue.h>
#include
<px4_defines.h>
#include
<drivers/drv_hrt.h>
#include
<systemlib/cpuload.h>
#include
<perf/perf_counter.h>
#include
<uORB/uORB.h>
#include
<uORB/topics/cpuload.h>
#include
<uORB/topics/task_stack_info.h>
#include
<uORB/uORB.h>
#if defined(__PX4_NUTTX) && !defined(CONFIG_SCHED_INSTRUMENTATION)
# error load_mon support requires CONFIG_SCHED_INSTRUMENTATION
...
...
@@ -75,7 +68,7 @@ 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
<
LoadMon
>
class
LoadMon
:
public
ModuleBase
<
LoadMon
>
,
public
ModuleParams
{
public:
LoadMon
();
...
...
@@ -103,7 +96,7 @@ private:
void
_cycle
();
/** Do a calculation of the CPU load and publish it. */
void
_c
ompute
();
void
_c
puload
();
/** Calculate the memory usage */
float
_ram_used
();
...
...
@@ -112,46 +105,28 @@ private:
/* Calculate stack usage */
void
_stack_usage
();
struct
task_stack_info_s
_task_stack_info
;
int
_stack_task_index
;
orb_advert_t
_task_stack_info_pub
;
int
_stack_task_index
{
0
};
orb_advert_t
_task_stack_info_pub
{
nullptr
};
#endif
struct
work_s
_work
;
DEFINE_PARAMETERS
(
(
ParamBool
<
px4
::
params
::
SYS_STCK_EN
>
)
_stack_check_enabled
)
work_s
_work
{};
orb_advert_t
_cpuload_pub
{
nullptr
};
hrt_abstime
_last_idle_time
{
0
};
hrt_abstime
_last_idle_time_sample
{
0
};
struct
cpuload_s
_cpuload
;
orb_advert_t
_cpuload_pub
;
hrt_abstime
_last_idle_time
;
perf_counter_t
_stack_perf
;
bool
_stack_check_enabled
;
};
LoadMon
::
LoadMon
()
:
#ifdef __PX4_NUTTX
_task_stack_info
{},
_stack_task_index
(
0
),
_task_stack_info_pub
(
nullptr
),
#endif
_work
{},
_cpuload
{},
_cpuload_pub
(
nullptr
),
_last_idle_time
(
0
),
_stack_perf
(
perf_alloc
(
PC_ELAPSED
,
"stack_check"
)),
_stack_check_enabled
(
false
)
ModuleParams
(
nullptr
),
_stack_perf
(
perf_alloc
(
PC_ELAPSED
,
"stack_check"
))
{
// Enable stack checking by param
param_t
param_stack_check
=
param_find
(
"SYS_STCK_EN"
);
if
(
param_stack_check
!=
PARAM_INVALID
)
{
int
ret_val
=
0
;
param_get
(
param_stack_check
,
&
ret_val
);
_stack_check_enabled
=
ret_val
>
0
;
// Only be verbose if enabled
if
(
_stack_check_enabled
)
{
PX4_INFO
(
"stack check enabled"
);
}
}
}
LoadMon
::~
LoadMon
()
...
...
@@ -191,7 +166,15 @@ LoadMon::cycle_trampoline(void *arg)
void
LoadMon
::
_cycle
()
{
_compute
();
_cpuload
();
#ifdef __PX4_NUTTX
if
(
_stack_check_enabled
.
get
())
{
_stack_usage
();
}
#endif
if
(
!
should_exit
())
{
work_queue
(
LPWORK
,
&
_work
,
(
worker_t
)
&
LoadMon
::
cycle_trampoline
,
this
,
...
...
@@ -202,7 +185,7 @@ void LoadMon::_cycle()
}
}
void
LoadMon
::
_c
ompute
()
void
LoadMon
::
_c
puload
()
{
if
(
_last_idle_time
==
0
)
{
/* Just get the time in the first iteration */
...
...
@@ -211,26 +194,23 @@ void LoadMon::_compute()
}
/* compute system load */
const
hrt_abstime
interval_idletime
=
system_load
.
tasks
[
0
].
total_runtime
-
_last_idle_time
;
_last_idle_time
=
system_load
.
tasks
[
0
].
total_runtime
;
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
;
_cpuload
.
timestamp
=
hrt_absolute_time
();
_cpuload
.
load
=
1.0
f
-
(
float
)
interval_idletime
/
(
float
)
LOAD_MON_INTERVAL_US
;
_cpuload
.
ram_usage
=
_ram_used
();
_last_idle_time
=
total_runtime
;
_last_idle_time_sample
=
hrt_absolute_time
();
#ifdef __PX4_NUTTX
if
(
_stack_check_enabled
)
{
_stack_usage
();
}
#endif
cpuload_s
cpuload
=
{};
cpuload
.
load
=
1.0
f
-
(
float
)
interval_idletime
/
(
float
)
interval
;
cpuload
.
ram_usage
=
_ram_used
();
cpuload
.
timestamp
=
hrt_absolute_time
();
if
(
_cpuload_pub
==
nullptr
)
{
_cpuload_pub
=
orb_advertise
(
ORB_ID
(
cpuload
),
&
_
cpuload
);
_cpuload_pub
=
orb_advertise
(
ORB_ID
(
cpuload
),
&
cpuload
);
}
else
{
orb_publish
(
ORB_ID
(
cpuload
),
_cpuload_pub
,
&
_
cpuload
);
orb_publish
(
ORB_ID
(
cpuload
),
_cpuload_pub
,
&
cpuload
);
}
}
...
...
@@ -243,7 +223,7 @@ float LoadMon::_ram_used()
mem
=
mallinfo
();
#else
(
void
)
mallinfo
(
&
mem
);
#endif
#endif
/* CONFIG_CAN_PASS_STRUCTS */
// mem.arena: total ram (bytes)
// mem.uordblks: used (bytes)
...
...
@@ -251,6 +231,7 @@ float LoadMon::_ram_used()
// mem.mxordblk: largest remaining block (bytes)
return
(
float
)
mem
.
uordblks
/
mem
.
arena
;
#else
return
0.0
f
;
#endif
...
...
@@ -273,11 +254,13 @@ void LoadMon::_stack_usage()
perf_begin
(
_stack_perf
);
sched_lock
();
task_stack_info_s
task_stack_info
=
{};
if
(
system_load
.
tasks
[
task_index
].
valid
&&
system_load
.
tasks
[
task_index
].
tcb
->
pid
>
0
)
{
stack_free
=
up_check_tcbstack_remain
(
system_load
.
tasks
[
task_index
].
tcb
);
strncpy
((
char
*
)
_
task_stack_info
.
task_name
,
system_load
.
tasks
[
task_index
].
tcb
->
name
,
strncpy
((
char
*
)
task_stack_info
.
task_name
,
system_load
.
tasks
[
task_index
].
tcb
->
name
,
task_stack_info_s
::
MAX_REPORT_TASK_NAME_LEN
);
#if CONFIG_NFILE_DESCRIPTORS > 0
...
...
@@ -305,21 +288,21 @@ void LoadMon::_stack_usage()
if
(
checked_task
)
{
_
task_stack_info
.
stack_free
=
stack_free
;
_
task_stack_info
.
timestamp
=
hrt_absolute_time
();
task_stack_info
.
stack_free
=
stack_free
;
task_stack_info
.
timestamp
=
hrt_absolute_time
();
if
(
_task_stack_info_pub
==
nullptr
)
{
_task_stack_info_pub
=
orb_advertise_queue
(
ORB_ID
(
task_stack_info
),
&
_
task_stack_info
,
num_tasks_per_cycle
);
_task_stack_info_pub
=
orb_advertise_queue
(
ORB_ID
(
task_stack_info
),
&
task_stack_info
,
num_tasks_per_cycle
);
}
else
{
orb_publish
(
ORB_ID
(
task_stack_info
),
_task_stack_info_pub
,
&
_
task_stack_info
);
orb_publish
(
ORB_ID
(
task_stack_info
),
_task_stack_info_pub
,
&
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
);
PX4_WARN
(
"%s low on stack! (%i bytes left)"
,
task_stack_info
.
task_name
,
stack_free
);
break
;
}
...
...
@@ -327,7 +310,7 @@ void LoadMon::_stack_usage()
* 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
);
PX4_WARN
(
"%s low on FDs! (%i FDs left)"
,
task_stack_info
.
task_name
,
fds_free
);
break
;
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment