summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-02-23 10:55:01 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-02-23 10:55:01 -0600
commit7c745cd460ea7361719b9fd18a35491beed92623 (patch)
treeb35642399f2cbe11bbe6c9a57f6cf2d90fea3ffb
parent875b32e8389ac6e06bfb328e992c1865445d96c1 (diff)
downloadpx4-nuttx-7c745cd460ea7361719b9fd18a35491beed92623.tar.gz
px4-nuttx-7c745cd460ea7361719b9fd18a35491beed92623.tar.bz2
px4-nuttx-7c745cd460ea7361719b9fd18a35491beed92623.zip
CPU load calculations now available for all threads. Available in /proc/pid/loadavg
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/fs/procfs/fs_procfscpuload.c40
-rw-r--r--nuttx/fs/procfs/fs_procfsproc.c83
-rw-r--r--nuttx/include/nuttx/clock.h45
-rw-r--r--nuttx/sched/Makefile4
-rw-r--r--nuttx/sched/os_internal.h29
-rw-r--r--nuttx/sched/sched_cpuload.c134
-rw-r--r--nuttx/sched/sched_processtimer.c37
-rw-r--r--nuttx/sched/sched_releasetcb.c9
-rw-r--r--nuttx/sched/task_setup.c10
10 files changed, 331 insertions, 64 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 990d0932d..3651571ee 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6657,3 +6657,7 @@
* 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).
+ * sched/sched_processtimer.c, sched_cpuload.c, fs/procfs/fs_procfscpuload.c,
+ and fs_procfscpuload.c: CPU load logic extended to keep counts on each
+ thread. The per-thread CPU is now reported in the procfs under
+ <pid>/loadavg (2014-2-23).
diff --git a/nuttx/fs/procfs/fs_procfscpuload.c b/nuttx/fs/procfs/fs_procfscpuload.c
index a1f8179bf..75572dee3 100644
--- a/nuttx/fs/procfs/fs_procfscpuload.c
+++ b/nuttx/fs/procfs/fs_procfscpuload.c
@@ -207,9 +207,6 @@ 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;
@@ -230,40 +227,37 @@ static ssize_t cpuload_read(FAR struct file *filep, FAR char *buffer,
if (filep->f_pos == 0)
{
- uint32_t idle;
- uint32_t busycnt;
- uint32_t verify;
+ struct cpuload_s cpuload;
+ uint32_t intpart;
+ uint32_t fracpart;
- /* Sample the counts, repeatedly if necessary to assure that they are
- * in sync.
+ /* Sample the counts for the IDLE thread. clock_cpuload should only
+ * fail if the PID is not valid. This, however, should never happen
+ * for the IDLE thread.
*/
- do
- {
- busycnt = g_cpuload.cnt;
- idle = g_cpuload.idle;
- verify = g_cpuload.cnt;
- }
- while (busycnt != verify);
+ DEBUGVERIFY(clock_cpuload(0, &cpuload));
- /* On the simulator, you may hit busycnt == 0, but probably never on
+ /* On the simulator, you may hit cpuload.total == 0, but probably never on
* real hardware.
*/
- if (busycnt > 0)
+ if (cpuload.total > 0)
{
- cpuload = 1000 - (1000 * idle) / busycnt;
- cpuload_int = cpuload / 10;
- cpuload_frac = cpuload - 10 * cpuload_int;
+ uint32_t tmp;
+
+ tmp = 1000 - (1000 * cpuload.active) / cpuload.total;
+ intpart = tmp / 10;
+ fracpart = tmp - 10 * intpart;
}
else
{
- cpuload_int = 0;
- cpuload_frac = 0;
+ intpart = 0;
+ fracpart = 0;
}
linesize = snprintf(attr->line, CPULOAD_LINELEN, "%3d.%01d%%\n",
- cpuload_int, cpuload_frac);
+ intpart, fracpart);
/* Save the linesize in case we are re-entered with f_pos > 0 */
diff --git a/nuttx/fs/procfs/fs_procfsproc.c b/nuttx/fs/procfs/fs_procfsproc.c
index 1fc90b096..a1ec1b898 100644
--- a/nuttx/fs/procfs/fs_procfsproc.c
+++ b/nuttx/fs/procfs/fs_procfsproc.c
@@ -60,6 +60,10 @@
#include <nuttx/fs/procfs.h>
#include <nuttx/fs/dirent.h>
+#ifdef CONFIG_SCHED_CPULOAD
+# include <nuttx/clock.h>
+#endif
+
#include <arch/irq.h>
#if !defined(CONFIG_DISABLE_MOUNTPOINT) && defined(CONFIG_FS_PROCFS)
@@ -86,6 +90,9 @@ enum proc_node_e
PROC_LEVEL0 = 0, /* The top-level directory */
PROC_STATUS, /* Task/thread status */
PROC_CMDLINE, /* Task command line */
+#ifdef CONFIG_SCHED_CPULOAD
+ PROC_LOADAVG, /* Average CPU utilization */
+#endif
PROC_STACK, /* Task stack info */
PROC_GROUP, /* Group directory */
PROC_GROUP_STATUS, /* Task group status */
@@ -136,6 +143,11 @@ static ssize_t proc_status(FAR struct proc_file_s *procfile,
static ssize_t proc_cmdline(FAR struct proc_file_s *procfile,
FAR struct tcb_s *tcb, FAR char *buffer, size_t buflen,
off_t offset);
+#ifdef CONFIG_SCHED_CPULOAD
+static ssize_t proc_loadavg(FAR struct proc_file_s *procfile,
+ FAR struct tcb_s *tcb, FAR char *buffer, size_t buflen,
+ off_t offset);
+#endif
static ssize_t proc_stack(FAR struct proc_file_s *procfile,
FAR struct tcb_s *tcb, FAR char *buffer, size_t buflen,
off_t offset);
@@ -211,6 +223,13 @@ static const struct proc_node_s g_cmdline =
"cmdline", "cmdline", (uint8_t)PROC_CMDLINE, DTYPE_FILE /* Task command line */
};
+#ifdef CONFIG_SCHED_CPULOAD
+static const struct proc_node_s g_loadavg =
+{
+ "loadavg", "loadavg", (uint8_t)PROC_LOADAVG, DTYPE_FILE /* Average CPU utilization */
+};
+#endif
+
static const struct proc_node_s g_stack =
{
"stack", "stack", (uint8_t)PROC_STACK, DTYPE_FILE /* Task stack info */
@@ -237,6 +256,9 @@ static FAR const struct proc_node_s * const g_nodeinfo[] =
{
&g_status, /* Task/thread status */
&g_cmdline, /* Task command line */
+#ifdef CONFIG_SCHED_CPULOAD
+ &g_loadavg, /* Average CPU utilization */
+#endif
&g_stack, /* Task stack info */
&g_group, /* Group directory */
&g_groupstatus, /* Task group status */
@@ -250,6 +272,9 @@ static const struct proc_node_s * const g_level0info[] =
{
&g_status, /* Task/thread status */
&g_cmdline, /* Task command line */
+#ifdef CONFIG_SCHED_CPULOAD
+ &g_loadavg, /* Average CPU utilization */
+#endif
&g_stack, /* Task stack info */
&g_group, /* Group directory */
};
@@ -518,12 +543,61 @@ static ssize_t proc_cmdline(FAR struct proc_file_s *procfile,
}
/****************************************************************************
+ * Name: proc_loadavg
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CPULOAD
+static ssize_t proc_loadavg(FAR struct proc_file_s *procfile,
+ FAR struct tcb_s *tcb, FAR char *buffer,
+ size_t buflen, off_t offset)
+{
+ struct cpuload_s cpuload;
+ uint32_t intpart;
+ uint32_t fracpart;
+ size_t linesize;
+ size_t copysize;
+ ssize_t ret;
+
+ /* Sample the counts for the thread. clock_cpuload should only fail if
+ * the PID is not valid. This could happen if the thread exited sometime
+ * after the procfs entry was opened.
+ */
+
+ ret = (ssize_t)clock_cpuload(procfile->pid, &cpuload);
+
+ /* On the simulator, you may hit cpuload.total == 0, but probably never on
+ * real hardware.
+ */
+
+ if (cpuload.total > 0)
+ {
+ uint32_t tmp;
+
+ tmp = 1000 - (1000 * cpuload.active) / cpuload.total;
+ intpart = tmp / 10;
+ fracpart = tmp - 10 * intpart;
+ }
+ else
+ {
+ intpart = 0;
+ fracpart = 0;
+ }
+
+ linesize = snprintf(procfile->line, STATUS_LINELEN, "%3d.%01d%%\n",
+ intpart, fracpart);
+ copysize = procfs_memcpy(procfile->line, linesize, buffer, buflen, &offset);
+
+ return copysize;
+}
+#endif
+
+/****************************************************************************
* Name: proc_stack
****************************************************************************/
static ssize_t proc_stack(FAR struct proc_file_s *procfile,
- FAR struct tcb_s *tcb, FAR char *buffer, size_t buflen,
- off_t offset)
+ FAR struct tcb_s *tcb, FAR char *buffer,
+ size_t buflen, off_t offset)
{
size_t remaining;
size_t linesize;
@@ -986,6 +1060,11 @@ static ssize_t proc_read(FAR struct file *filep, FAR char *buffer,
ret = proc_cmdline(procfile, tcb, buffer, buflen, filep->f_pos);
break;
+#ifdef CONFIG_SCHED_CPULOAD
+ case PROC_LOADAVG: /* Average CPU utilization */
+ ret = proc_loadavg(procfile, tcb, buffer, buflen, filep->f_pos);
+ break;
+#endif
case PROC_STACK: /* Task stack info */
ret = proc_stack(procfile, tcb, buffer, buflen, filep->f_pos);
break;
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index d0fd9220f..d1315fbba 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -124,13 +124,13 @@
/****************************************************************************
* Public Types
****************************************************************************/
-/* This structure is used when CONFIG_SCHED_CPULOAD to sample CPU usage */
+/* This structure is used to report CPU usage for a particular thread */
#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 */
+ volatile uint32_t total; /* Total number of clock ticks */
+ volatile uint32_t active; /* Number of ticks while this thread was active */
};
#endif
@@ -162,20 +162,14 @@ 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
-
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -209,7 +203,7 @@ extern "C" {
****************************************************************************/
#ifdef CONFIG_RTC
-EXTERN void clock_synchronize(void);
+void clock_synchronize(void);
#endif
/****************************************************************************
@@ -235,7 +229,7 @@ EXTERN void clock_synchronize(void);
# ifdef CONFIG_SYSTEM_TIME64
# define clock_systimer() (uint32_t)(clock_systimer64() & 0x00000000ffffffff)
# else
-EXTERN uint32_t clock_systimer(void);
+uint32_t clock_systimer(void);
# endif
#endif
@@ -259,7 +253,30 @@ EXTERN uint32_t clock_systimer(void);
****************************************************************************/
#if !__HAVE_KERNEL_GLOBALS && defined(CONFIG_SYSTEM_TIME64)
-EXTERN uint64_t clock_systimer64(void);
+uint64_t clock_systimer64(void);
+#endif
+
+/****************************************************************************
+ * Function: clock_cpuload
+ *
+ * Description:
+ * Return load measurement data for the select PID.
+ *
+ * Parameters:
+ * pid - The task ID of the thread of interest. pid == 0 is the IDLE thread.
+ * cpuload - The location to return the CPU load
+ *
+ * Return Value:
+ * OK (0) on success; a negated errno value on failure. The only reason
+ * that this function can fail is if 'pid' no longer refers to a valid
+ * thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CPULOAD
+int clock_cpuload(int pid, FAR struct cpuload_s *cpuload);
#endif
#undef EXTERN
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index a9ee0dc3e..67da182ab 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -93,6 +93,10 @@ SCHED_SRCS += sched_waitid.c sched_wait.c
endif
endif
+ifeq ($(CONFIG_SCHED_CPULOAD),y)
+SCHED_SRCS += sched_cpuload.c
+endif
+
GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c
GRP_SRCS += group_setupstreams.c group_setupidlefiles.c group_setuptaskfiles.c
GRP_SRCS += task_getgroup.c group_foreachchild.c group_killchildren.c
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 6073bb39f..999e7c3df 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/os_internal.h
*
- * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -81,15 +81,24 @@
* Public Type Definitions
****************************************************************************/
-/* This structure defines the format of the hash table that
- * is used to (1) determine if a task ID is unique, and (2)
- * to map a process ID to its corresponding TCB.
+/* This structure defines the format of the hash table that is used to (1)
+ * determine if a task ID is unique, and (2) to map a process ID to its
+ * corresponding TCB.
+ *
+ * NOTE also that CPU load measurement data is retained in his table vs. in
+ * the TCB which would seem to be the more logic place. It is place in the
+ * hash table, instead, to facilitate CPU load adjustments on all threads
+ * during timer interrupt handling. sched_foreach() could do this too, but
+ * this would require a little more overhead.
*/
struct pidhash_s
{
- FAR struct tcb_s *tcb;
- pid_t pid;
+ FAR struct tcb_s *tcb; /* TCB assigned to this PID */
+ pid_t pid; /* The full PID value */
+#ifdef CONFIG_SCHED_CPULOAD
+ uint32_t ticks; /* Number of ticks on this thread */
+#endif
};
typedef struct pidhash_s pidhash_t;
@@ -210,6 +219,14 @@ extern pidhash_t g_pidhash[CONFIG_MAX_TASKS];
extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
+#ifdef CONFIG_SCHED_CPULOAD
+/* This is the total number of clock tick counts. Essentially the
+ * 'denominator' for all CPU load calculations.
+ */
+
+extern volatile uint32_t g_cpuload_total;
+#endif
+
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
diff --git a/nuttx/sched/sched_cpuload.c b/nuttx/sched/sched_cpuload.c
new file mode 100644
index 000000000..03f7656c1
--- /dev/null
+++ b/nuttx/sched/sched_cpuload.c
@@ -0,0 +1,134 @@
+/************************************************************************
+ * sched/sched_cpuload.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 <errno.h>
+#include <assert.h>
+
+#include <nuttx/clock.h>
+#include <arch/irq.h>
+
+#include "os_internal.h"
+
+#ifdef CONFIG_SCHED_CPULOAD
+
+/************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Public Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/****************************************************************************
+ * Function: clock_cpuload
+ *
+ * Description:
+ * Return load measurement data for the select PID.
+ *
+ * Parameters:
+ * pid - The task ID of the thread of interest. pid == 0 is the IDLE thread.
+ * cpuload - The location to return the CPU load
+ *
+ * Return Value:
+ * OK (0) on success; a negated errno value on failure. The only reason
+ * that this function can fail is if 'pid' no longer refers to a valid
+ * thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int clock_cpuload(int pid, FAR struct cpuload_s *cpuload)
+{
+ irqstate_t flags;
+ int hash_index = PIDHASH(pid);
+ int ret = -ESRCH;
+
+ DEBUGASSERT(cpuload);
+
+ /* Momentarily disable interrupts. We need (1) the task to stay valid
+ * while we are doing these operations and (2) the tick counts to be
+ * synchronized when read.
+ */
+
+ flags = irqsave();
+
+ /* Make sure that the entry is valid (TCB field is not NULL) and matches
+ * the requested PID. The first check is needed if the thread has exited.
+ * The second check is needed for the case where the task associated with
+ * the requested PID has exited and the slot has been taken by another
+ * thread with a different PID.
+ *
+ * NOTE also that CPU load measurement data is retained in the g_pidhash
+ * table vs. in the TCB which would seem to be the more logic place. It
+ * is place in the hash table, instead, to facilitate CPU load adjustments
+ * on all threads during timer interrupt handling. sched_foreach() could
+ * do this too, but this would require a little more overhead.
+ */
+
+ if (g_pidhash[hash_index].tcb && g_pidhash[hash_index].pid == pid)
+ {
+ cpuload->total = g_cpuload_total;
+ cpuload->active = g_pidhash[hash_index].ticks;
+ ret = OK;
+ }
+
+ irqrestore(flags);
+ return ret;
+}
+
+#endif /* CONFIG_SCHED_CPULOAD */
diff --git a/nuttx/sched/sched_processtimer.c b/nuttx/sched/sched_processtimer.c
index b07994cb4..c03077c21 100644
--- a/nuttx/sched/sched_processtimer.c
+++ b/nuttx/sched/sched_processtimer.c
@@ -63,13 +63,15 @@
************************************************************************/
/************************************************************************
- * Global Variables
+ * Public Variables
************************************************************************/
-/* This structure is used when CONFIG_SCHED_CPULOAD to sample CPU usage */
-
#ifdef CONFIG_SCHED_CPULOAD
-volatile struct cpuload_s g_cpuload;
+/* This is the total number of clock tick counts. Essentially the
+ * 'denominator' for all CPU load calculations.
+ */
+
+volatile uint32_t g_cpuload_total;
#endif
/************************************************************************
@@ -170,27 +172,34 @@ static inline void sched_process_timeslice(void)
*
************************************************************************/
-#if defined(CONFIG_SCHED_CPULOAD)
+#ifdef CONFIG_SCHED_CPULOAD
static inline void sched_process_cpuload(void)
{
FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ int hash_index;
+ int i;
- /* Gather stats for cpuload. cpuload is percent of time cpu is not idle. */
- /* Is the idle task running */
+ /* Increment the count on the currently executing thread */
- if (rtcb->pid == 0)
- {
- ++g_cpuload.idle;
- }
+ hash_index = PIDHASH(rtcb->pid);
+ g_pidhash[hash_index].ticks++;
/* 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))
+ if (++g_cpuload_total > (CONFIG_SCHED_CPULOAD_TIMECONSTANT * CLOCKS_PER_SEC))
{
- g_cpuload.cnt >>= 1;
- g_cpuload.idle >>= 1;
+ /* Divide the tick count for every task by two */
+
+ for (i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ g_pidhash[i].ticks >>= 1;
+ }
+
+ /* Divide the total tick count by two */
+
+ g_cpuload_total >>= 1;
}
}
#else
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 26476ec98..2b184fbda 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_releasetcb.c
*
- * Copyright (C) 2007, 2009, 2012-2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2012-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,8 +68,11 @@ static void sched_releasepid(pid_t pid)
* following action is atomic
*/
- g_pidhash[hash_ndx].tcb = NULL;
- g_pidhash[hash_ndx].pid = INVALID_PROCESS_ID;
+ g_pidhash[hash_ndx].tcb = NULL;
+ g_pidhash[hash_ndx].pid = INVALID_PROCESS_ID;
+#ifdef CONFIG_SCHED_CPULOAD
+ g_pidhash[hash_ndx].ticks = 0;
+#endif
}
/************************************************************************
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 582b64a4a..ed1578da9 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -132,9 +132,15 @@ static int task_assignpid(FAR struct tcb_s *tcb)
if (!g_pidhash[hash_ndx].tcb)
{
- g_pidhash[hash_ndx].tcb = tcb;
- g_pidhash[hash_ndx].pid = next_pid;
+ /* Assign this PID to the task */
+
+ g_pidhash[hash_ndx].tcb = tcb;
+ g_pidhash[hash_ndx].pid = next_pid;
+#ifdef CONFIG_SCHED_CPULOAD
+ g_pidhash[hash_ndx].ticks = 0;
+#endif
tcb->pid = next_pid;
+
(void)sched_unlock();
return OK;
}