summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-02-22 15:20:12 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-02-22 15:20:12 -0600
commitd75e62056261d8f75ec5b1b4fb9fd61d4768c163 (patch)
tree09a09c84a6490999f87162b2973d64ce0f0941f8 /nuttx
parentb28a177cf7e0fb330a25c67b81fd3027ce72171d (diff)
downloadpx4-nuttx-d75e62056261d8f75ec5b1b4fb9fd61d4768c163.tar.gz
px4-nuttx-d75e62056261d8f75ec5b1b4fb9fd61d4768c163.tar.bz2
px4-nuttx-d75e62056261d8f75ec5b1b4fb9fd61d4768c163.zip
Add logic to meaure and calculate the CPU load percentage. From David Alessio
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/configs/sim/nsh/defconfig2
-rw-r--r--nuttx/configs/sim/nxlines/defconfig3
-rw-r--r--nuttx/configs/sim/nxwm/defconfig2
-rw-r--r--nuttx/fs/procfs/Kconfig25
-rw-r--r--nuttx/fs/procfs/Make.defs1
-rw-r--r--nuttx/fs/procfs/fs_procfs.c15
-rw-r--r--nuttx/fs/procfs/fs_procfscpuload.c358
-rw-r--r--nuttx/fs/procfs/fs_procfsproc.c4
-rw-r--r--nuttx/include/nuttx/clock.h28
-rw-r--r--nuttx/sched/Kconfig24
-rw-r--r--nuttx/sched/sched_processtimer.c85
12 files changed, 525 insertions, 26 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 911692bc5..990d0932d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6654,4 +6654,6 @@
where the apps/ directly will reside until configuration time (2014-2-21).
* arch/arm/src/sam34/chip/sam4e_pinmap.h: SAM4E pin multiplexing
definitions (2014-2-21).
-
+ * sched/sched_processtimer.c and fs/procfs/fs_procfscpuload.c: Add
+ logic to measure and calculate the CPU load percentage. From David
+ Alessio (2014-2-22).
diff --git a/nuttx/configs/sim/nsh/defconfig b/nuttx/configs/sim/nsh/defconfig
index 01cb4521a..37f2a1497 100644
--- a/nuttx/configs/sim/nsh/defconfig
+++ b/nuttx/configs/sim/nsh/defconfig
@@ -455,6 +455,8 @@ CONFIG_EXAMPLES_NSH=y
# NSH Library
#
CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_READLINE=y
+# CONFIG_NSH_CLE is not set
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_FILE_APPS=y
diff --git a/nuttx/configs/sim/nxlines/defconfig b/nuttx/configs/sim/nxlines/defconfig
index 046ca3e18..e3a68aacd 100644
--- a/nuttx/configs/sim/nxlines/defconfig
+++ b/nuttx/configs/sim/nxlines/defconfig
@@ -479,6 +479,9 @@ CONFIG_EXAMPLES_NXLINES_BPP=32
# NSH Library
#
CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_READLINE=y
+# CONFIG_NSH_CLE is not set
+
#
# Disable Individual commands
diff --git a/nuttx/configs/sim/nxwm/defconfig b/nuttx/configs/sim/nxwm/defconfig
index f5ead1cb2..5821f2c39 100644
--- a/nuttx/configs/sim/nxwm/defconfig
+++ b/nuttx/configs/sim/nxwm/defconfig
@@ -547,6 +547,8 @@ CONFIG_HAVE_CXX=y
# NSH Library
#
CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_READLINE=y
+# CONFIG_NSH_CLE is not set
#
# Disable Individual commands
diff --git a/nuttx/fs/procfs/Kconfig b/nuttx/fs/procfs/Kconfig
index 84df4a620..ff10519fe 100644
--- a/nuttx/fs/procfs/Kconfig
+++ b/nuttx/fs/procfs/Kconfig
@@ -17,16 +17,6 @@ if FS_PROCFS
menu "Exclude individual procfs entries"
-config FS_PROCFS_EXCLUDE_MOUNTS
- bool "Exclude mounts"
- depends on !DISABLE_MOUNTPOINT
- default n
-
-config FS_PROCFS_EXCLUDE_MTD
- bool "Exclude mtd"
- depends on MTD
- default n
-
config FS_PROCFS_EXCLUDE_PROCESS
bool "Exclude process information"
default n
@@ -39,6 +29,21 @@ config FS_PROCFS_EXCLUDE_UPTIME
bool "Exclude uptime"
default n
+config FS_PROCFS_EXCLUDE_CPULOAD
+ bool "Exclude CPU load"
+ default n
+ depends on SCHED_CPULOAD
+
+config FS_PROCFS_EXCLUDE_MOUNTS
+ bool "Exclude mounts"
+ default n
+ depends on !DISABLE_MOUNTPOINT
+
+config FS_PROCFS_EXCLUDE_MTD
+ bool "Exclude mtd"
+ depends on MTD
+ default n
+
config FS_PROCFS_EXCLUDE_PARTITIONS
bool "Exclude partitions"
depends on MTD_PARTITION
diff --git a/nuttx/fs/procfs/Make.defs b/nuttx/fs/procfs/Make.defs
index 8b05cbb17..dfe17aff4 100644
--- a/nuttx/fs/procfs/Make.defs
+++ b/nuttx/fs/procfs/Make.defs
@@ -38,6 +38,7 @@ ifeq ($(CONFIG_FS_PROCFS),y)
ASRCS +=
CSRCS += fs_procfs.c fs_procfsutil.c fs_procfsproc.c fs_procfsuptime.c
+CSRCS += fs_procfscpuload.c
# Include procfs build support
diff --git a/nuttx/fs/procfs/fs_procfs.c b/nuttx/fs/procfs/fs_procfs.c
index e52c6dca2..f1d98d0a7 100644
--- a/nuttx/fs/procfs/fs_procfs.c
+++ b/nuttx/fs/procfs/fs_procfs.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/procfs/fs_procfs.c
*
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -69,13 +69,14 @@
* Pre-processor Definitions
****************************************************************************/
-#define PROCFS_NATTRS 2
+#define PROCFS_NATTRS 2
/****************************************************************************
* External Definitons
****************************************************************************/
extern const struct procfs_operations proc_operations;
+extern const struct procfs_operations cpuload_operations;
extern const struct procfs_operations uptime_operations;
extern const struct procfs_operations mtd_procfsoperations;
extern const struct procfs_operations part_procfsoperations;
@@ -92,23 +93,31 @@ static const struct procfs_entry_s g_procfsentries[] =
{ "[0-9]*/**", &proc_operations },
{ "[0-9]*", &proc_operations },
#endif
+
+#if defined(CONFIG_SCHED_CPULOAD) && !defined(CONFIG_FS_PROCFS_EXCLUDE_CPULOAD)
+ { "cpuload", &cpuload_operations },
+#endif
+
#if defined(CONFIG_FS_SMARTFS) && !defined(CONFIG_FS_PROCFS_EXCLUDE_SMARTFS)
//{ "fs/smartfs", &smartfs_procfsoperations },
{ "fs/smartfs**", &smartfs_procfsoperations },
#endif
+
#if defined(CONFIG_MTD) && !defined(CONFIG_FS_PROCFS_EXCLUDE_MTD)
{ "mtd", &mtd_procfsoperations },
#endif
+
#if defined(CONFIG_MTD_PARTITION) && !defined(CONFIG_FS_PROCFS_EXCLUDE_PARTITON)
{ "partitions", &part_procfsoperations },
#endif
+
#if !defined(CONFIG_FS_PROCFS_EXCLUDE_UPTIME)
{ "uptime", &uptime_operations },
#endif
};
static const uint8_t g_procfsentrycount = sizeof(g_procfsentries) /
- sizeof(struct procfs_entry_s);
+ sizeof(struct procfs_entry_s);
/****************************************************************************
* Private Function Prototypes
diff --git a/nuttx/fs/procfs/fs_procfscpuload.c b/nuttx/fs/procfs/fs_procfscpuload.c
new file mode 100644
index 000000000..a1f8179bf
--- /dev/null
+++ b/nuttx/fs/procfs/fs_procfscpuload.c
@@ -0,0 +1,358 @@
+/****************************************************************************
+ * fs/procfs/fs_procfscpuload.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/statfs.h>
+#include <sys/stat.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <time.h>
+#include <string.h>
+#include <fcntl.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/clock.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/fs/fs.h>
+#include <nuttx/fs/procfs.h>
+
+#if !defined(CONFIG_DISABLE_MOUNTPOINT) && defined(CONFIG_FS_PROCFS)
+#ifndef CONFIG_FS_PROCFS_EXCLUDE_CPULOAD
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Determines the size of an intermediate buffer that must be large enough
+ * to handle the longest line generated by this logic.
+ */
+
+#define CPULOAD_LINELEN 16
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure describes one open "file" */
+
+struct cpuload_file_s
+{
+ struct procfs_file_s base; /* Base open file structure */
+ unsigned int linesize; /* Number of valid characters in line[] */
+ char line[CPULOAD_LINELEN]; /* Pre-allocated buffer for formatted lines */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* File system methods */
+
+static int cpuload_open(FAR struct file *filep, FAR const char *relpath,
+ int oflags, mode_t mode);
+static int cpuload_close(FAR struct file *filep);
+static ssize_t cpuload_read(FAR struct file *filep, FAR char *buffer,
+ size_t buflen);
+static int cpuload_dup(FAR const struct file *oldp,
+ FAR struct file *newp);
+static int cpuload_stat(FAR const char *relpath, FAR struct stat *buf);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/* See fs_mount.c -- this structure is explicitly externed there.
+ * We use the old-fashioned kind of initializers so that this will compile
+ * with any compiler.
+ */
+
+const struct procfs_operations cpuload_operations =
+{
+ cpuload_open, /* open */
+ cpuload_close, /* close */
+ cpuload_read, /* read */
+ NULL, /* write */
+
+ cpuload_dup, /* dup */
+
+ NULL, /* opendir */
+ NULL, /* closedir */
+ NULL, /* readdir */
+ NULL, /* rewinddir */
+
+ cpuload_stat /* stat */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: cpuload_open
+ ****************************************************************************/
+
+static int cpuload_open(FAR struct file *filep, FAR const char *relpath,
+ int oflags, mode_t mode)
+{
+ FAR struct cpuload_file_s *attr;
+
+ fvdbg("Open '%s'\n", relpath);
+
+ /* PROCFS is read-only. Any attempt to open with any kind of write
+ * access is not permitted.
+ *
+ * REVISIT: Write-able proc files could be quite useful.
+ */
+
+ if ((oflags & O_WRONLY) != 0 || (oflags & O_RDONLY) == 0)
+ {
+ fdbg("ERROR: Only O_RDONLY supported\n");
+ return -EACCES;
+ }
+
+ /* "cpuload" is the only acceptable value for the relpath */
+
+ if (strcmp(relpath, "cpuload") != 0)
+ {
+ fdbg("ERROR: relpath is '%s'\n", relpath);
+ return -ENOENT;
+ }
+
+ /* Allocate a container to hold the file attributes */
+
+ attr = (FAR struct cpuload_file_s *)kzalloc(sizeof(struct cpuload_file_s));
+ if (!attr)
+ {
+ fdbg("ERROR: Failed to allocate file attributes\n");
+ return -ENOMEM;
+ }
+
+ /* Save the attributes as the open-specific state in filep->f_priv */
+
+ filep->f_priv = (FAR void *)attr;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: cpuload_close
+ ****************************************************************************/
+
+static int cpuload_close(FAR struct file *filep)
+{
+ FAR struct cpuload_file_s *attr;
+
+ /* Recover our private data from the struct file instance */
+
+ attr = (FAR struct cpuload_file_s *)filep->f_priv;
+ DEBUGASSERT(attr);
+
+ /* Release the file attributes structure */
+
+ kfree(attr);
+ filep->f_priv = NULL;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: cpuload_read
+ ****************************************************************************/
+
+static ssize_t cpuload_read(FAR struct file *filep, FAR char *buffer,
+ size_t buflen)
+{
+ FAR struct cpuload_file_s *attr;
+ uint32_t cpuload;
+ uint32_t cpuload_int;
+ uint32_t cpuload_frac;
+ size_t linesize;
+ off_t offset;
+ ssize_t ret;
+
+ fvdbg("buffer=%p buflen=%d\n", buffer, (int)buflen);
+
+ /* Recover our private data from the struct file instance */
+
+ attr = (FAR struct cpuload_file_s *)filep->f_priv;
+ DEBUGASSERT(attr);
+
+ /* If f_pos is zero, then sample the system time. Otherwise, use
+ * the cached system time from the previous read(). It is necessary
+ * save the cached value in case, for example, the user is reading
+ * the time one byte at a time. In that case, the time must remain
+ * stable throughout the reads.
+ */
+
+ if (filep->f_pos == 0)
+ {
+ uint32_t idle;
+ uint32_t busycnt;
+ uint32_t verify;
+
+ /* Sample the counts, repeatedly if necessary to assure that they are
+ * in sync.
+ */
+
+ do
+ {
+ busycnt = g_cpuload.cnt;
+ idle = g_cpuload.idle;
+ verify = g_cpuload.cnt;
+ }
+ while (busycnt != verify);
+
+ /* On the simulator, you may hit busycnt == 0, but probably never on
+ * real hardware.
+ */
+
+ if (busycnt > 0)
+ {
+ cpuload = 1000 - (1000 * idle) / busycnt;
+ cpuload_int = cpuload / 10;
+ cpuload_frac = cpuload - 10 * cpuload_int;
+ }
+ else
+ {
+ cpuload_int = 0;
+ cpuload_frac = 0;
+ }
+
+ linesize = snprintf(attr->line, CPULOAD_LINELEN, "%3d.%01d%%\n",
+ cpuload_int, cpuload_frac);
+
+ /* Save the linesize in case we are re-entered with f_pos > 0 */
+
+ attr->linesize = linesize;
+ }
+
+ /* Transfer the system up time to user receive buffer */
+
+ offset = filep->f_pos;
+ ret = procfs_memcpy(attr->line, attr->linesize, buffer, buflen, &offset);
+
+ /* Update the file offset */
+
+ if (ret > 0)
+ {
+ filep->f_pos += ret;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: cpuload_dup
+ *
+ * Description:
+ * Duplicate open file data in the new file structure.
+ *
+ ****************************************************************************/
+
+static int cpuload_dup(FAR const struct file *oldp, FAR struct file *newp)
+{
+ FAR struct cpuload_file_s *oldattr;
+ FAR struct cpuload_file_s *newattr;
+
+ fvdbg("Dup %p->%p\n", oldp, newp);
+
+ /* Recover our private data from the old struct file instance */
+
+ oldattr = (FAR struct cpuload_file_s *)oldp->f_priv;
+ DEBUGASSERT(oldattr);
+
+ /* Allocate a new container to hold the task and attribute selection */
+
+ newattr = (FAR struct cpuload_file_s *)kmalloc(sizeof(struct cpuload_file_s));
+ if (!newattr)
+ {
+ fdbg("ERROR: Failed to allocate file attributes\n");
+ return -ENOMEM;
+ }
+
+ /* The copy the file attributes from the old attributes to the new */
+
+ memcpy(newattr, oldattr, sizeof(struct cpuload_file_s));
+
+ /* Save the new attributes in the new file structure */
+
+ newp->f_priv = (FAR void *)newattr;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: cpuload_stat
+ *
+ * Description: Return information about a file or directory
+ *
+ ****************************************************************************/
+
+static int cpuload_stat(const char *relpath, struct stat *buf)
+{
+ /* "cpuload" is the only acceptable value for the relpath */
+
+ if (strcmp(relpath, "cpuload") != 0)
+ {
+ fdbg("ERROR: relpath is '%s'\n", relpath);
+ return -ENOENT;
+ }
+
+ /* "cpuload" is the name for a read-only file */
+
+ buf->st_mode = S_IFREG|S_IROTH|S_IRGRP|S_IRUSR;
+ buf->st_size = 0;
+ buf->st_blksize = 0;
+ buf->st_blocks = 0;
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* CONFIG_FS_PROCFS_EXCLUDE_CPULOAD */
+#endif /* !CONFIG_DISABLE_MOUNTPOINT && CONFIG_FS_PROCFS */
diff --git a/nuttx/fs/procfs/fs_procfsproc.c b/nuttx/fs/procfs/fs_procfsproc.c
index bd87f21b2..1fc90b096 100644
--- a/nuttx/fs/procfs/fs_procfsproc.c
+++ b/nuttx/fs/procfs/fs_procfsproc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/procfs/fs_procfsproc.c
*
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,7 +68,7 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* Determines the size of an intermeidate buffer that must be large enough
+/* Determines the size of an intermediate buffer that must be large enough
* to handle the longest line generated by this logic.
*/
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index e640ecd2e..d0fd9220f 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/clock.h
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2012, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,7 +47,7 @@
#include <nuttx/compiler.h>
/****************************************************************************
- * Pro-processor Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Efficient, direct access to OS global timer variables will be supported
@@ -122,7 +122,20 @@
#define TICK2SEC(tick) (((tick)+(TICK_PER_SEC/2))/TICK_PER_SEC) /* Rounds */
/****************************************************************************
- * Global Data
+ * Public Types
+ ****************************************************************************/
+/* This structure is used when CONFIG_SCHED_CPULOAD to sample CPU usage */
+
+#ifdef CONFIG_SCHED_CPULOAD
+struct cpuload_s
+{
+ volatile uint32_t cnt; /* Total number of clock ticks */
+ volatile uint32_t idle; /* Total number of clocks ticks with CPU IDLE */
+};
+#endif
+
+/****************************************************************************
+ * Public Data
****************************************************************************/
#if !defined(CONFIG_DISABLE_CLOCK)
@@ -149,8 +162,15 @@ extern volatile uint32_t g_system_timer;
# endif
#endif
+/* CPU Load Measurements ***************************************************/
+/* This structure is used when CONFIG_SCHED_CPULOAD to sample CPU usage */
+
+#ifdef CONFIG_SCHED_CPULOAD
+extern volatile struct cpuload_s g_cpuload;
+#endif
+
/****************************************************************************
- * Global Function Prototypes
+ * Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index 8aeda33ea..a6b661e05 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -60,6 +60,30 @@ config RR_INTERVAL
The round robin timeslice will be set this number of milliseconds;
Round robin scheduling can be disabled by setting this value to zero.
+config SCHED_CPULOAD
+ bool "Enable CPU load monitoring"
+ default n
+ ---help---
+ If this option is selected, the timer interrupt handler will monitor
+ if the system is IDLE or busy at the time of that the timer interrupt
+ occurs. This is a very coarse measurement, but over a period of time,
+ it can very accurately determined the percentage of the time that the
+ CPU is IDLE.
+
+ The statistics collected in this could be used, for example in the
+ PROCFS file system to provide CPU load measurements when read.
+
+if SCHED_CPULOAD
+
+config SCHED_CPULOAD_TIMECONSTANT
+ int "CPU load time constant"
+ default 2
+ ---help---
+ The accumulated CPU count is divided by two when the accumulated
+ tick count exceeds this time constant.
+
+endif # SCHED_CPULOAD
+
config SCHED_INSTRUMENTATION
bool "Monitor system performance"
default n
diff --git a/nuttx/sched/sched_processtimer.c b/nuttx/sched/sched_processtimer.c
index a065d007e..b07994cb4 100644
--- a/nuttx/sched/sched_processtimer.c
+++ b/nuttx/sched/sched_processtimer.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_processtimer.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
+#include <time.h>
#if CONFIG_RR_INTERVAL > 0
# include <sched.h>
@@ -50,8 +51,12 @@
#include "clock_internal.h"
/************************************************************************
- * Definitions
+ * Pre-processor Definitions
************************************************************************/
+
+#ifndef CONFIG_SCHED_CPULOAD_TIMECONSTANT
+# define CONFIG_SCHED_CPULOAD_TIMECONSTANT 2
+#endif
/************************************************************************
* Private Type Declarations
@@ -61,6 +66,12 @@
* Global Variables
************************************************************************/
+/* This structure is used when CONFIG_SCHED_CPULOAD to sample CPU usage */
+
+#ifdef CONFIG_SCHED_CPULOAD
+volatile struct cpuload_s g_cpuload;
+#endif
+
/************************************************************************
* Private Variables
************************************************************************/
@@ -69,16 +80,29 @@
* Private Functions
************************************************************************/
-static void sched_process_timeslice(void)
-{
+/************************************************************************
+ * Name: sched_process_timeslice
+ *
+ * Description:
+ * Check if the currently executing task has exceeded its time slice.
+ *
+ * Inputs:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
#if CONFIG_RR_INTERVAL > 0
- struct tcb_s *rtcb;
+static inline void sched_process_timeslice(void)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
/* Check if the currently executing task uses round robin
* scheduling.
*/
- rtcb = (struct tcb_s*)g_readytorun.head;
if ((rtcb->flags & TCB_FLAG_ROUND_ROBIN) != 0)
{
/* Yes, check if decrementing the timeslice counter
@@ -127,8 +151,51 @@ static void sched_process_timeslice(void)
rtcb->timeslice--;
}
}
+}
+#else
+# define sched_process_timeslice()
#endif
+
+/************************************************************************
+ * Name: sched_process_cpuload
+ *
+ * Description:
+ * Collect data that can be used for CPU load measurements.
+ *
+ * Inputs:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+#if defined(CONFIG_SCHED_CPULOAD)
+static inline void sched_process_cpuload(void)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+
+ /* Gather stats for cpuload. cpuload is percent of time cpu is not idle. */
+ /* Is the idle task running */
+
+ if (rtcb->pid == 0)
+ {
+ ++g_cpuload.idle;
+ }
+
+ /* Increment tick count. If the accumulated tick value exceed a time
+ * constant, then shift the accumulators.
+ */
+
+ if (++g_cpuload.cnt > (CONFIG_SCHED_CPULOAD_TIMECONSTANT * CLOCKS_PER_SEC))
+ {
+ g_cpuload.cnt >>= 1;
+ g_cpuload.idle >>= 1;
+ }
}
+#else
+# define sched_process_cpuload()
+#endif
/************************************************************************
* Public Functions
@@ -173,6 +240,12 @@ void sched_process_timer(void)
}
#endif
+ /* Perform CPU load measurements (before any timer-initiated context switches
+ * can occur)
+ */
+
+ sched_process_cpuload();
+
/* Process watchdogs (if in the link) */
#ifdef CONFIG_HAVE_WEAKFUNCTIONS