summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-28 21:42:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-28 21:42:18 +0000
commit94c7babe23d72a1e379da0cf0aab32fcf9fadcf3 (patch)
treeeedc930a4ed4a1108c87cae26d3fcda7e411dd1f
parent405c2b328ff4cd571bb9e464541b4d297b18f93d (diff)
downloadpx4-nuttx-94c7babe23d72a1e379da0cf0aab32fcf9fadcf3.tar.gz
px4-nuttx-94c7babe23d72a1e379da0cf0aab32fcf9fadcf3.tar.bz2
px4-nuttx-94c7babe23d72a1e379da0cf0aab32fcf9fadcf3.zip
atexit() functions now called when task killed by task delete; For MCUs with <= 64Kb of SRAM, CONFIG_MM_SMALL can be defined to reduce the memory allocation overhead
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3648 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--apps/examples/ostest/barrier.c10
-rw-r--r--apps/examples/ostest/ostest.h14
-rw-r--r--apps/examples/ostest/posixtimer.c8
-rw-r--r--apps/examples/ostest/prioinherit.c28
-rw-r--r--apps/examples/ostest/sighand.c22
-rw-r--r--apps/examples/ostest/timedmqueue.c6
-rw-r--r--apps/examples/ostest/timedwait.c6
-rw-r--r--nuttx/ChangeLog21
-rw-r--r--nuttx/Documentation/NuttX.html22
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html13
-rw-r--r--nuttx/TODO33
-rw-r--r--nuttx/arch/sim/src/up_allocateheap.c2
-rw-r--r--nuttx/arch/sim/src/up_internal.h9
-rw-r--r--nuttx/configs/README.txt9
-rw-r--r--nuttx/include/nuttx/sched.h4
-rw-r--r--nuttx/mm/mm_environment.h3
-rw-r--r--nuttx/mm/mm_initialize.c21
-rw-r--r--nuttx/mm/mm_internal.h64
-rw-r--r--nuttx/mm/mm_malloc.c2
-rw-r--r--nuttx/mm/mm_memalign.c2
-rw-r--r--nuttx/mm/mm_test.c1
-rw-r--r--nuttx/sched/Makefile10
-rw-r--r--nuttx/sched/exit.c59
-rw-r--r--nuttx/sched/os_internal.h1
-rw-r--r--nuttx/sched/task_delete.c16
-rw-r--r--nuttx/sched/task_exithook.c157
26 files changed, 376 insertions, 167 deletions
diff --git a/apps/examples/ostest/barrier.c b/apps/examples/ostest/barrier.c
index c88e1bed1..da1301dc3 100644
--- a/apps/examples/ostest/barrier.c
+++ b/apps/examples/ostest/barrier.c
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/ostest/barrier.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,6 +77,7 @@ static void *barrier_func(void *parameter)
printf("barrier_func: Thread %d calling pthread_barrier_wait()\n",
id);
+ FFLUSH();
status = pthread_barrier_wait(&barrier);
if (status == 0)
{
@@ -95,11 +96,13 @@ static void *barrier_func(void *parameter)
printf("barrier_func: ERROR thread %d could not get semaphore value\n",
id);
}
+ FFLUSH();
#ifndef CONFIG_DISABLE_SIGNALS
usleep(HALF_SECOND);
#endif
printf("barrier_func: Thread %d done\n", id);
+ FFLUSH();
return NULL;
}
@@ -158,12 +161,15 @@ void barrier_test(void)
{
printf("barrier_test: Error in thread %d create, status=%d\n",
i, status);
+ printf("barrier_test: Test aborted with waiting threads\n");
+ goto abort_test;
}
else
{
printf("barrier_test: Thread %d created\n", i);
}
}
+ FFLUSH();
/* Wait for all thread instances to complete */
@@ -184,6 +190,7 @@ void barrier_test(void)
/* Destroy the barrier */
+abort_test:
status = pthread_barrier_destroy(&barrier);
if (status != OK)
{
@@ -197,4 +204,5 @@ void barrier_test(void)
printf("barrier_test: pthread_barrierattr_destroy failed, status=%d\n",
status);
}
+ FFLUSH();
}
diff --git a/apps/examples/ostest/ostest.h b/apps/examples/ostest/ostest.h
index 1cd705898..99290828e 100644
--- a/apps/examples/ostest/ostest.h
+++ b/apps/examples/ostest/ostest.h
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/ostest/ostest.h
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -79,6 +79,18 @@
# define dump_nfreeholders(s)
#endif
+/* If CONFIG_STDIO_LINEBUFFER is defined, the STDIO buffer will be flushed
+ * on each new line. Otherwise, STDIO needs to be explicitly flushed to
+ * see the output in context.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && \
+ CONFIG_STDIO_BUFFER_SIZE > 0 && !defined(CONFIG_STDIO_LINEBUFFER)
+# define FFLUSH() fflush(stdout)
+#else
+# define FFLUSH()
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/apps/examples/ostest/posixtimer.c b/apps/examples/ostest/posixtimer.c
index 457b4c1a2..3560c712b 100644
--- a/apps/examples/ostest/posixtimer.c
+++ b/apps/examples/ostest/posixtimer.c
@@ -1,7 +1,7 @@
/***********************************************************************
* examples/ostest/posixtimer.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -56,12 +56,6 @@
#define MY_TIMER_SIGNAL 17
#define SIGVALUE_INT 42
-#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
-# define FFLUSH() fflush(stdout)
-#else
-# define FFLUSH()
-#endif
-
/**************************************************************************
* Private Data
**************************************************************************/
diff --git a/apps/examples/ostest/prioinherit.c b/apps/examples/ostest/prioinherit.c
index 5d59c1297..993c9e14a 100644
--- a/apps/examples/ostest/prioinherit.c
+++ b/apps/examples/ostest/prioinherit.c
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/ostest/prioinherit.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -139,7 +139,7 @@ static void *highpri_thread(void *parameter)
g_highstate[threadno-1] = RUNNING;
printf("highpri_thread-%d: Started\n", threadno);
- fflush(stdout);
+ FFLUSH();
sleep(1);
printf("highpri_thread-%d: Calling sem_wait()\n", threadno);
@@ -162,7 +162,7 @@ static void *highpri_thread(void *parameter)
sem_post(&g_sem);
printf("highpri_thread-%d: Okay... I'm done!\n", threadno);
- fflush(stdout);
+ FFLUSH();
return NULL;
}
@@ -202,7 +202,7 @@ static void *medpri_thread(void *parameter)
{
printf("medpri_thread: Started ... I won't let go of the CPU!\n");
g_middlestate = RUNNING;
- fflush(stdout);
+ FFLUSH();
/* The following loop will completely block lowpri_thread from running.
* UNLESS priority inheritance is working. In that case, its priority
@@ -215,7 +215,7 @@ static void *medpri_thread(void *parameter)
}
printf("medpri_thread: Okay... I'm done!\n");
- fflush(stdout);
+ FFLUSH();
g_middlestate = DONE;
return NULL;
}
@@ -273,7 +273,7 @@ static void *lowpri_thread(void *parameter)
}
printf(" I still have a count on the semaphore\n");
sem_enumholders(&g_sem);
- fflush(stdout);
+ FFLUSH();
sleep(1);
}
@@ -365,7 +365,7 @@ static void *lowpri_thread(void *parameter)
sem_enumholders(&g_sem);
printf("lowpri_thread-%d: Okay... I'm done!\n", threadno);
- fflush(stdout);
+ FFLUSH();
g_lowstate[threadno-1] = DONE;
return retval;
}
@@ -466,7 +466,7 @@ void priority_inheritance(void)
{
printf("priority_inheritance: Set medpri_thread priority to %d\n", sparam.sched_priority);
}
- fflush(stdout);
+ FFLUSH();
status = pthread_create(&medpri, &attr, medpri_thread, NULL);
if (status != 0)
@@ -501,7 +501,7 @@ void priority_inheritance(void)
printf("priority_inheritance: Set highpri_thread-%d priority to %d\n",
threadno, sparam.sched_priority);
}
- fflush(stdout);
+ FFLUSH();
status = pthread_create(&highpri[i], &attr, highpri_thread, (void*)threadno);
if (status != 0)
@@ -510,25 +510,25 @@ void priority_inheritance(void)
}
}
dump_nfreeholders("priority_inheritance:");
- fflush(stdout);
+ FFLUSH();
/* Wait for all thread instances to complete */
for (i = 0; i < NHIGHPRI_THREADS; i++)
{
printf("priority_inheritance: Waiting for highpri_thread-%d to complete\n", i+1);
- fflush(stdout);
+ FFLUSH();
(void)pthread_join(highpri[i], &result);
dump_nfreeholders("priority_inheritance:");
}
printf("priority_inheritance: Waiting for medpri_thread to complete\n");
- fflush(stdout);
+ FFLUSH();
(void)pthread_join(medpri, &result);
dump_nfreeholders("priority_inheritance:");
for (i = 0; i < NLOWPRI_THREADS; i++)
{
printf("priority_inheritance: Waiting for lowpri_thread-%d to complete\n", i+1);
- fflush(stdout);
+ FFLUSH();
(void)pthread_join(lowpri[i], &result);
dump_nfreeholders("priority_inheritance:");
}
@@ -536,6 +536,6 @@ void priority_inheritance(void)
printf("priority_inheritance: Finished\n");
sem_destroy(&g_sem);
dump_nfreeholders("priority_inheritance:");
- fflush(stdout);
+ FFLUSH();
#endif /* CONFIG_PRIORITY_INHERITANCE && !CONFIG_DISABLE_SIGNALS && !CONFIG_DISABLE_PTHREAD */
}
diff --git a/apps/examples/ostest/sighand.c b/apps/examples/ostest/sighand.c
index 66f98cb58..681531639 100644
--- a/apps/examples/ostest/sighand.c
+++ b/apps/examples/ostest/sighand.c
@@ -152,10 +152,7 @@ static int waiter_main(int argc, char *argv[])
/* Take the semaphore */
printf("waiter_main: Waiting on semaphore\n" );
-
-#if CONFIG_NFILE_STREAMS > 0
- fflush(stdout);
-#endif
+ FFLUSH();
status = sem_wait(&sem);
if (status != 0)
@@ -181,10 +178,7 @@ static int waiter_main(int argc, char *argv[])
status = sigaction(WAKEUP_SIGNAL, &act, &oact);
printf("waiter_main: done\n" );
-
-#if CONFIG_NFILE_STREAMS > 0
- fflush(stdout);
-#endif
+ FFLUSH();
threadexited = true;
return 0;
@@ -231,9 +225,7 @@ void sighand_test(void)
/* Wait a bit */
-#if CONFIG_NFILE_STREAMS > 0
- fflush(stdout);
-#endif
+ FFLUSH();
sleep(2);
/* Then signal the waiter thread. */
@@ -255,9 +247,7 @@ void sighand_test(void)
/* Wait a bit */
-#if CONFIG_NFILE_STREAMS > 0
- fflush(stdout);
-#endif
+ FFLUSH();
sleep(2);
/* Then check the result */
@@ -273,7 +263,5 @@ void sighand_test(void)
}
printf("sighand_test: done\n" );
-#if CONFIG_NFILE_STREAMS > 0
- fflush(stdout);
-#endif
+ FFLUSH();
}
diff --git a/apps/examples/ostest/timedmqueue.c b/apps/examples/ostest/timedmqueue.c
index 84b8913b2..807d8537b 100644
--- a/apps/examples/ostest/timedmqueue.c
+++ b/apps/examples/ostest/timedmqueue.c
@@ -69,12 +69,6 @@
#define TEST_SEND_NMSGS (10)
#define TEST_RECEIVE_NMSGS (10)
-#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
-# define FFLUSH() fflush(stdout)
-#else
-# define FFLUSH()
-#endif
-
/**************************************************************************
* Private Types
**************************************************************************/
diff --git a/apps/examples/ostest/timedwait.c b/apps/examples/ostest/timedwait.c
index 24edb463b..fc381ddda 100644
--- a/apps/examples/ostest/timedwait.c
+++ b/apps/examples/ostest/timedwait.c
@@ -49,12 +49,6 @@
* Private Definitions
**************************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
-# define FFLUSH() fflush(stdout)
-#else
-# define FFLUSH()
-#endif
-
/**************************************************************************
* Private Data
**************************************************************************/
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 76f4f2c97..e4f09183b 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1548,7 +1548,7 @@
* sched/atexit.c and sched/exit.c: The atexit function is not frequently
used. In order to save a few bytes, it is now conditioned on
CONFIG_SCHED_ATEXIT. It your application is currently using atexit(),
- you will need to add CONFIG_SCHED_ATEXT to your configuration file.
+ you will need to add CONFIG_SCHED_ATEXIT to your configuration file.
* drivers/net/slip.c: Add a SLIP driver (untested on initial check-in).
* configs/olimex-lpc1766stk/slip-httpd: An example that uses SLIP to
provide a serial-port based THTTPD web server.
@@ -1770,7 +1770,22 @@
the MPLAB debugger on PIC32; I will need to get a PICkit 3).
* drivers/net/e1000.c/h: A PCI-based E1000 ethernet driver submitted
by Yu Qiang.
- * lib/net/lib_inetaddr.c: An implementatino of the inet_addr() function
- submitted y Yu Qiang.
+ * lib/net/lib_inetaddr.c: An implementation of the inet_addr() function
+ submitted by Yu Qiang.
* arch/arm/src/lpc31xx and arch/arm/include/lpc31xx: Renamed from lpc313x
to make name space for other famiy members.
+ * arch/arm/*/lpc31xx: Added support for the LPC315x family (untested).
+ * sched/task_exithook.c: Functionality performed when a task exits or is
+ deleted has been moved to a common file task_exithook.c. Now exit()
+ functionality (like flushing I/O and calling registered atexit()
+ functions, etc.) will be performed when a task is deleted as well.
+ * mm/: Added support for CONFIG_MM_SMALL. Each memory allocation has a
+ small allocation overhead. The size of that overhead is normally
+ determined by the "width" of the address support by the MCU. MCUs
+ that support 16-bit addressability have smaller overhead than devices
+ that support 32-bit addressability. However, there are many MCUs
+ that support 32-bit addressability *but* have internal SRAM of size
+ less than or equal to 64Kb. In this case, CONFIG_MM_SMALL can be
+ defined so that those MCUs will also benefit from the smaller, 16-
+ bit-based allocation overhead.
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index b29bf7ab0..84548e10d 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: May 25, 2011</p>
+ <p>Last Updated: May 28, 2011</p>
</td>
</tr>
</table>
@@ -2313,8 +2313,24 @@ nuttx-6.4 2011-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
the MPLAB debugger on PIC32; I will need to get a PICkit 3).
* drivers/net/e1000.c/h: A PCI-based E1000 ethernet driver submitted
by Yu Qiang.
- * lib/net/lib_inetaddr.c: An implementatino of the inet_addr() function
- submitted y Yu Qiang.
+ * lib/net/lib_inetaddr.c: An implementation of the inet_addr() function
+ submitted by Yu Qiang.
+ * arch/arm/src/lpc31xx and arch/arm/include/lpc31xx: Renamed from lpc313x
+ to make name space for other famiy members.
+ * arch/arm/*/lpc31xx: Added support for the LPC315x family (untested).
+ * sched/task_exithook.c: Functionality performed when a task exits or is
+ deleted has been moved to a common file task_exithook.c. Now exit()
+ functionality (like flushing I/O and calling registered atexit()
+ functions, etc.) will be performed when a task is deleted as well.
+ * mm/: Added support for CONFIG_MM_SMALL. Each memory allocation has a
+ small allocation overhead. The size of that overhead is normally
+ determined by the &quot;width&quot; of the address support by the MCU. MCUs
+ that support 16-bit addressability have smaller overhead than devices
+ that support 32-bit addressability. However, there are many MCUs
+ that support 32-bit addressability *but* have internal SRAM of size
+ less than or equal to 64Kb. In this case, CONFIG_MM_SMALL can be
+ defined so that those MCUs will also benefit from the smaller, 16-
+ bit-based allocation overhead.
apps-6.4 2011-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index fb06f794e..faa9f32cf 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
- <p>Last Updated: May 25, 2011</p>
+ <p>Last Updated: May 28, 2011</p>
</td>
</tr>
</table>
@@ -3263,6 +3263,17 @@ build
handle and enables the API mm_addregion(start, end);
</li>
<li>
+ <code>CONFIG_MM_SMALL</code>: Each memory allocation has a small allocation
+ overhead. The size of that overhead is normally determined by
+ the &quot;width&quot; of the address support by the MCU. MCUs that support
+ 16-bit addressability have smaller overhead than devices that
+ support 32-bit addressability. However, there are many MCUs
+ that support 32-bit addressability <i>but</i> have internal SRAM
+ of size less than or equal to 64Kb. In this case, CONFIG_MM_SMALL
+ can be defined so that those MCUs will also benefit from the
+ smaller, 16-bit-based allocation overhead.
+ </li>
+ <li>
<code>CONFIG_MSEC_PER_TICK</code>: The default system timer is 100Hz
or <code>MSEC_PER_TICK</code>=10. This setting may be defined to inform NuttX
that the processor hardware is providing system timer interrupts at some interrupt
diff --git a/nuttx/TODO b/nuttx/TODO
index 25722f3f0..553c79ec2 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -1,11 +1,11 @@
-NuttX TODO List (Last updated May 14, 2011)
+NuttX TODO List (Last updated May 28, 2011)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
nuttx/
(5) Task/Scheduler (sched/)
(1) On-demand paging (sched/)
- (2) Memory Managment (mm/)
+ (1) Memory Managment (mm/)
(1) Signals (sched/, arch/)
(1) pthreads (sched/)
(1) C++ Support
@@ -40,7 +40,7 @@ nuttx/
apps/
(5) Network Utilities (apps/netutils/)
- (4) NuttShell (NSH) (apps/nshlib)
+ (5) NuttShell (NSH) (apps/nshlib)
(3) Other Applications & Tests (apps/examples/)
o Task/Scheduler (sched/)
@@ -51,13 +51,12 @@ o Task/Scheduler (sched/)
Status: Open
Priority: Medium, required for good emulation of process/pthread model.
- Description: atexit() supports registration of one function called on exit().
- Should task_delete() also cause atexit() function to be called?
- Update: atexit() is only built into the system if CONFIG_SCHED_ATEXT
- is defined in the configuration.
+ Description: atexit() supports registration of only single function called on
+ exit(). It should support multiple functions registered by atexit()
+ or onexit() and these should be called in reverse order of
+ registration when the task exits.
Status: Open
- Priority: Low, task_delete() is non-standard and its behavior is
- unspecified.
+ Priority: Low
Description: Implement sys/mman.h and functions
Status: Open
@@ -121,13 +120,6 @@ o Memory Managment (mm/)
Priority: Medium/Low, a good feature to prevent memory leaks but would
have negative impact on memory usage and code size.
- Description: Current logic adapts size_t for 16-bit address machines vs.
- 32-bit address machines. But a small memory option should also
- be provided so that the small offset option can be used with
- 32-bit machines that have small RAM memories (like the lpc2148)
- Status: Open
- Priority: High, a good feature enhancement.
-
o Signals (sched/, arch/)
^^^^^^^^^^^^^^^^^^^^^^^
@@ -329,7 +321,7 @@ o Network (net/, drivers/net)
Description: The interfaces used to leave/join IGMP multicast groups is non-standard.
RFC3678 (IGMPv3) suggests ioctl() commands to do this (SIOCSIPMSFILTER) but
also status that those APIs are historic. NuttX implements these ioctl
- commnands, but is non-standard because: (1) It does not support IGMPv3, and
+ commands, but is non-standard because: (1) It does not support IGMPv3, and
(2) it looks up drivers by their device name (eg., "eth0") vs IP address.
Linux uses setsockopt() to control multicast group membership using the
@@ -1196,6 +1188,13 @@ o NuttShell (NSH) (apps/nshlib)
Status: Open
Priority: Med-High
+ Descripton: The ifconfig command will not behave correctly is an interface
+ is provided and there are multiple interfaces. It should only
+ show status for the single interface on the command line; it will
+ still show status for all interfaces.
+ Status: Open
+ Priority: Low (multiple network interfaces not fully supported yet anyway).
+
Description: Add support to NSH to run NXFLAT programs from a ROMFS file system
Status: Open
Priority: Low (enhancement)
diff --git a/nuttx/arch/sim/src/up_allocateheap.c b/nuttx/arch/sim/src/up_allocateheap.c
index 9278faf27..f02f8cbfa 100644
--- a/nuttx/arch/sim/src/up_allocateheap.c
+++ b/nuttx/arch/sim/src/up_allocateheap.c
@@ -81,5 +81,5 @@ static uint8_t sim_heap[SIM_HEAP_SIZE];
void up_allocate_heap(void **heap_start, size_t *heap_size)
{
*heap_start = sim_heap;
- *heap_size = SIM_HEAP_SIZE;
+ *heap_size = SIM_HEAP_SIZE;
}
diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h
index 7f241e48e..094776390 100644
--- a/nuttx/arch/sim/src/up_internal.h
+++ b/nuttx/arch/sim/src/up_internal.h
@@ -40,6 +40,7 @@
* Included Files
**************************************************************************/
+#include <nuttx/config.h>
#include <sys/types.h>
#include <nuttx/irq.h>
@@ -64,7 +65,13 @@
# define JB_PC (5)
#endif /* __ASSEMBLY__ */
-#define SIM_HEAP_SIZE (4*1024*1024)
+/* Size of the simulated heap */
+
+#if CONFIG_MM_SMALL
+# define SIM_HEAP_SIZE (64*1024)
+#else
+# define SIM_HEAP_SIZE (4*1024*1024)
+#endif
/* These definitions characterize the compressed filesystem image */
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index d00fe1e20..509e57281 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -261,6 +261,15 @@ defconfig -- This is a configuration file similar to the Linux
regions of memory to allocate from, this specifies the
number of memory regions that the memory manager must
handle and enables the API mm_addregion(start, end);
+ CONFIG_MM_SMALL - Each memory allocation has a small allocation
+ overhead. The size of that overhead is normally determined by
+ the "width" of the address support by the MCU. MCUs that support
+ 16-bit addressability have smaller overhead than devices that
+ support 32-bit addressability. However, there are many MCUs
+ that support 32-bit addressability *but* have internal SRAM
+ of size less than or equal to 64Kb. In this case, CONFIG_MM_SMALL
+ can be defined so that those MCUs will also benefit from the
+ smaller, 16-bit-based allocation overhead.
CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
or MSEC_PER_TICK=10. This setting may be defined to
inform NuttX that the processor hardware is providing
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 78e6f6b37..8256c2d8c 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -137,7 +137,7 @@ typedef union entry_u entry_t;
* (if registered via atexit()).
*/
-#ifdef CONFIG_SCHED_ATEXT
+#ifdef CONFIG_SCHED_ATEXIT
typedef void (*exitfunc_t)(void);
#endif
@@ -184,7 +184,7 @@ struct _TCB
pid_t pid; /* This is the ID of the thread */
start_t start; /* Thread start function */
entry_t entry; /* Entry Point into the thread */
-#ifdef CONFIG_SCHED_ATEXT
+#ifdef CONFIG_SCHED_ATEXIT
exitfunc_t exitfunc; /* Called if exit is called. */
#endif
#ifdef CONFIG_SCHED_WAITPID /* Experimental */
diff --git a/nuttx/mm/mm_environment.h b/nuttx/mm/mm_environment.h
index 3525eccc0..ef4f14f7a 100644
--- a/nuttx/mm/mm_environment.h
+++ b/nuttx/mm/mm_environment.h
@@ -1,7 +1,7 @@
/****************************************************************************
* mm/mm_environment.h
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -76,6 +76,7 @@
# define FAR /* Normally in compiler.h */
# define CONFIG_CPP_HAVE_VARARGS 1 /* Normally in compiler.h */
# define CONFIG_MM_REGIONS 2 /* Normally in config.h */
+# undef CONFIG_MM_SMALL /* Normally in config.h */
# define CONFIG_CAN_PASS_STRUCTS 1 /* Normally in config.h */
# undef CONFIG_SMALL_MEMORY /* Normally in config.h */
diff --git a/nuttx/mm/mm_initialize.c b/nuttx/mm/mm_initialize.c
index 9a580cd89..351948c2f 100644
--- a/nuttx/mm/mm_initialize.c
+++ b/nuttx/mm/mm_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* mm/mm_initialize.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -124,7 +124,7 @@ void mm_initialize(FAR void *heapstart, size_t heapsize)
}
/* Initialize the malloc semaphore to one (to support one-at-
- * a-time access to private data sets.
+ * a-time access to private data sets).
*/
mm_seminitialize();
@@ -155,20 +155,29 @@ void mm_initialize(FAR void *heapstart, size_t heapsize)
void mm_addregion(FAR void *heapstart, size_t heapsize)
{
FAR struct mm_freenode_s *node;
- size_t heapbase;
- size_t heapend;
+ uintptr_t heapbase;
+ uintptr_t heapend;
#if CONFIG_MM_REGIONS > 1
int IDX = g_nregions;
#else
# define IDX 0
#endif
+ /* If the MCU handles wide addresses but the memory manager
+ * is configured for a small heap, then verify that the caller
+ * not doing something crazy.
+ */
+
+#if defined(CONFIG_MM_SMALL) && !defined(CONFIG_SMALL_MEMORY)
+ DEBUGASSERT(heapsize <= MMSIZE_MAX+1);
+#endif
+
/* Adjust the provide heap start and size so that they are
* both aligned with the MM_MIN_CHUNK size.
*/
- heapbase = MM_ALIGN_UP((size_t)heapstart);
- heapend = MM_ALIGN_DOWN((size_t)heapstart + (size_t)heapsize);
+ heapbase = MM_ALIGN_UP((uintptr_t)heapstart);
+ heapend = MM_ALIGN_DOWN((uintptr_t)heapstart + (uintptr_t)heapsize);
heapsize = heapend - heapbase;
mlldbg("Region %d: base=%p size=%u\n", IDX+1, heapstart, heapsize);
diff --git a/nuttx/mm/mm_internal.h b/nuttx/mm/mm_internal.h
index 0649122a2..429559328 100644
--- a/nuttx/mm/mm_internal.h
+++ b/nuttx/mm/mm_internal.h
@@ -1,7 +1,7 @@
/************************************************************************
* mm/mm_internal.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,7 +43,24 @@
/************************************************************************
* Pre-processor Definitions
************************************************************************/
+/* Configuration ********************************************************/
+/* If the MCU has a small (16-bit) address capability, then we will use
+ * a smaller chunk header that contains 16-bit size/offset information.
+ * We will also use the smaller header on MCUs with wider addresses if
+ * CONFIG_MM_SMALL is selected. This configuration is common with MCUs
+ * that have a large FLASH space, but only a tiny internal SRAM.
+ */
+
+#ifdef CONFIG_SMALL_MEMORY
+ /* If the MCU has a small addressing capability, then for the smaller
+ * chunk header.
+ */
+
+# undef CONFIG_MM_SMALL
+# define CONFIG_MM_SMALL 1
+#endif
+/* Chunk Header Definitions *********************************************/
/* These definitions define the characteristics of allocator
*
* MM_MIN_SHIFT is used to define MM_MIN_CHUNK.
@@ -61,7 +78,7 @@
* losses.
*/
-#ifdef CONFIG_SMALL_MEMORY
+#ifdef CONFIG_MM_SMALL
# define MM_MIN_SHIFT 4 /* 16 bytes */
# define MM_MAX_SHIFT 15 /* 32 Kb */
#else
@@ -84,7 +101,7 @@
* an allocated chunk.
*/
-#ifdef CONFIG_SMALL_MEMORY
+#ifdef CONFIG_MM_SMALL
# define MM_ALLOC_BIT 0x8000
#else
# define MM_ALLOC_BIT 0x80000000
@@ -96,18 +113,30 @@
* Public Types
************************************************************************/
+/* Determine the size of the chunk size/offset type */
+
+#ifdef CONFIG_MM_SMALL
+ typedef uint16_t mmsize_t;
+# define MMSIZE_MAX 0xffff
+#else
+ typedef size_t mmsize_t;
+# define MMSIZE_MAX SIZE_MAX
+#endif
+
/* This describes an allocated chunk. An allocated chunk is
- * distinguished from a free chunk by bit 31 of the 'precding'
- * chunk size. If set, then this is an allocated chunk.
+ * distinguished from a free chunk by bit 15/31 of the 'preceding' chunk
+ * size. If set, then this is an allocated chunk.
*/
struct mm_allocnode_s
{
- size_t size; /* Size of this chunk */
- size_t preceding; /* Size of the preceding chunk */
+ mmsize_t size; /* Size of this chunk */
+ mmsize_t preceding; /* Size of the preceding chunk */
};
-#ifdef CONFIG_SMALL_MEMORY
+/* What is the size of the allocnode? */
+
+#ifdef CONFIG_MM_SMALL
# define SIZEOF_MM_ALLOCNODE 4
#else
# define SIZEOF_MM_ALLOCNODE 8
@@ -120,18 +149,25 @@ struct mm_allocnode_s
struct mm_freenode_s
{
- size_t size; /* Size of this chunk */
- size_t preceding; /* Size of the preceding chunk */
+ mmsize_t size; /* Size of this chunk */
+ mmsize_t preceding; /* Size of the preceding chunk */
FAR struct mm_freenode_s *flink; /* Supports a doubly linked list */
FAR struct mm_freenode_s *blink;
};
-#ifdef CONFIG_SMALL_MEMORY
-# define SIZEOF_MM_FREENODE 8
+/* Free is the size of the freenode */
+
+#ifdef CONFIG_MM_SMALL
+# ifdef CONFIG_SMALL_MEMORY
+# define SIZEOF_MM_FREENODE 8
+# else
+# define SIZEOF_MM_FREENODE 12
+# endif
#else
-# define SIZEOF_MM_FREENODE 16
+# define SIZEOF_MM_FREENODE 16
#endif
-#define CHECK_FREENODE_SIZE \
+
+#define CHECK_FREENODE_SIZE \
DEBUGASSERT(sizeof(struct mm_freenode_s) == SIZEOF_MM_FREENODE)
/* Normally defined in stdlib.h */
diff --git a/nuttx/mm/mm_malloc.c b/nuttx/mm/mm_malloc.c
index 5d5257716..dbcba33a8 100644
--- a/nuttx/mm/mm_malloc.c
+++ b/nuttx/mm/mm_malloc.c
@@ -199,6 +199,6 @@ FAR void *malloc(size_t size)
}
mm_givesemaphore();
- mvdbg("Allocated %p\n", ret);
+ mvdbg("Allocated %p, size %d\n", ret, size);
return ret;
}
diff --git a/nuttx/mm/mm_memalign.c b/nuttx/mm/mm_memalign.c
index a4d9cabd5..d40f72348 100644
--- a/nuttx/mm/mm_memalign.c
+++ b/nuttx/mm/mm_memalign.c
@@ -94,7 +94,7 @@ FAR void *memalign(size_t alignment, size_t size)
* The do not include SIZEOF_MM_ALLOCNODE.
*/
- size = MM_ALIGN_UP(size); /* Make mutliples of our granule size */
+ size = MM_ALIGN_UP(size); /* Make multiples of our granule size */
allocsize = size + 2*alignment; /* Add double full alignment size */
/* Then malloc that size */
diff --git a/nuttx/mm/mm_test.c b/nuttx/mm/mm_test.c
index 48f380221..e7a44dec7 100644
--- a/nuttx/mm/mm_test.c
+++ b/nuttx/mm/mm_test.c
@@ -41,6 +41,7 @@
#define FAR
#define CONFIG_MM_REGIONS 2
+#undef CONFIG_MM_SMALL
#define CONFIG_CAN_PASS_STRUCTS 1
#undef CONFIG_SMALL_MEMORY
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 859bd57b4..9ea7ca1ba 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -44,11 +44,11 @@ MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c \
sched_setuppthreadfiles.c sched_releasefiles.c
TSK_SRCS = task_create.c task_init.c task_setup.c task_activate.c \
- task_start.c task_delete.c task_deletecurrent.c task_restart.c \
- exit.c atexit.c getpid.c sched_addreadytorun.c sched_removereadytorun.c \
- sched_addprioritized.c sched_mergepending.c sched_addblocked.c \
- sched_removeblocked.c sched_free.c sched_gettcb.c sched_verifytcb.c \
- sched_releasetcb.c
+ task_start.c task_delete.c task_deletecurrent.c task_exithook.c \
+ task_restart.c exit.c atexit.c getpid.c sched_addreadytorun.c \
+ sched_removereadytorun.c sched_addprioritized.c sched_mergepending.c \
+ sched_addblocked.c sched_removeblocked.c sched_free.c sched_gettcb.c \
+ sched_verifytcb.c sched_releasetcb.c
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c \
sched_setscheduler.c sched_getscheduler.c \
diff --git a/nuttx/sched/exit.c b/nuttx/sched/exit.c
index 6793eae77..2964b5a01 100644
--- a/nuttx/sched/exit.c
+++ b/nuttx/sched/exit.c
@@ -67,7 +67,7 @@
****************************************************************************/
/****************************************************************************
- * Private Functionss
+ * Private Functions
****************************************************************************/
/****************************************************************************
@@ -78,68 +78,29 @@
* Function: exit
*
* Description:
- * The exit() function causes normal process termination
- * and the value of status & 0377 is returned to the parent.
+ * The exit() function causes normal process termination and the value of
+ * status & 0377 to be returned to the parent.
*
- * All functions registered with atexit() and on_exit() are
- * called, in the reverse order of their registration.
+ * All functions registered with atexit() and on_exit() are called, in the
+ * reverse order of their registration.
*
- * All open streams are flushed and closed. Files created
- * by tmpfile() are removed.
+ * All open streams are flushed and closed.
*
****************************************************************************/
void exit(int status)
{
-#if CONFIG_NFILE_STREAMS > 0 || defined(CONFIG_SCHED_WAITPID) || defined(CONFIG_SCHED_ATEXIT)
_TCB *tcb = (_TCB*)g_readytorun.head;
-#endif
- /* Only the lower 8 bits of the exit status are used */
+ /* Only the lower 8-bits of status are used */
status &= 0xff;
- /* Flush all streams (File descriptors will be closed when
- * the TCB is deallocated.
- */
+ /* Perform common task termination logic */
-#if CONFIG_NFILE_STREAMS > 0
- (void)lib_flushall(tcb->streams);
-#endif
+ task_exithook(tcb, status);
- /* Wakeup any tasks waiting for this task to exit */
-
-#ifdef CONFIG_SCHED_WAITPID /* Experimental */
- while (tcb->exitsem.semcount < 0)
- {
- /* "If more than one thread is suspended in waitpid() awaiting
- * termination of the same process, exactly one thread will return
- * the process status at the time of the target process termination."
- * Hmmm.. what do we return to the others?
- */
-
- if (tcb->stat_loc)
- {
- *tcb->stat_loc = status << 8;
- tcb->stat_loc = NULL;
- }
-
- /* Wake up the thread */
-
- sem_post(&tcb->exitsem);
- }
-#endif
-
- /* If an exit function was registered, call it now. */
-
-#ifdef CONFIG_SCHED_ATEXIT
- if (tcb->exitfunc)
- {
- (*tcb->exitfunc)();
- }
-#endif
-
- /* Then "really" exit */
+ /* Then "really" exit. Only the lower 8 bits of the exit status are used. */
_exit(status);
}
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index b25ee1c5e..3287507a9 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -265,6 +265,7 @@ extern void task_start(void);
extern int task_schedsetup(FAR _TCB *tcb, int priority, start_t start,
main_t main);
extern int task_argsetup(FAR _TCB *tcb, const char *name, const char *argv[]);
+extern void task_exithook(FAR _TCB *tcb, int status);
extern int task_deletecurrent(void);
#ifndef CONFIG_CUSTOM_STACK
extern int kernel_thread(const char *name, int priority,
diff --git a/nuttx/sched/task_delete.c b/nuttx/sched/task_delete.c
index 4fd49a4ea..51b3e30da 100644
--- a/nuttx/sched/task_delete.c
+++ b/nuttx/sched/task_delete.c
@@ -140,14 +140,9 @@ int task_delete(pid_t pid)
PANIC(OSERR_BADDELETESTATE);
}
- saved_state = irqsave();
-
- /* Inform the instrumentation layer that the task has stopped */
-
- sched_note_stop(dtcb);
-
/* Remove the task from the OS's tasks lists. */
+ saved_state = irqsave();
dq_rem((FAR dq_entry_t*)dtcb, (dq_queue_t*)g_tasklisttable[dtcb->task_state].list);
dtcb->task_state = TSTATE_TASK_INVALID;
irqrestore(saved_state);
@@ -156,11 +151,12 @@ int task_delete(pid_t pid)
sched_unlock();
- /* Deallocate anything left in the TCB's queues */
+ /* Perform common task termination logic (flushing streams, calling
+ * functions registered by at_exit/on_exit, etc.). I suppose EXIT_SUCCESS
+ * is an appropriate return value???
+ */
-#ifndef CONFIG_DISABLE_SIGNALS
- sig_cleanup(dtcb); /* Deallocate Signal lists */
-#endif
+ task_exithook(dtcb, EXIT_SUCCESS);
/* Deallocate its TCB */
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
new file mode 100644
index 000000000..9567f48a9
--- /dev/null
+++ b/nuttx/sched/task_exithook.c
@@ -0,0 +1,157 @@
+/****************************************************************************
+ * sched/task_exithook.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <stdlib.h>
+#include <unistd.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+
+#include "os_internal.h"
+#include "sig_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: task_hook
+ *
+ * Description:
+ * This function implements some of the internal logic of exit() and
+ * task_delete(). This function performs some cleanup and other actions
+ * required when a task exists:
+ *
+ * - All open streams are flushed and closed.
+ * - All functions registered with atexit() and on_exit() are called, in
+ * the reverse order of their registration.
+ *
+ * When called from exit(), the tcb still resides at the head of the ready-
+ * to-run list. The following logic is safe because we will not be
+ * returning from the exit() call.
+ *
+ * When called from task_delete() we are operating on a different thread;
+ * on the thread that called task_delete(). In this case, task_delete
+ * will have already removed the tcb from the ready-to-run list to prevent
+ * any further action on this task.
+ *
+ ****************************************************************************/
+
+void task_exithook(FAR _TCB *tcb, int status)
+{
+ /* Inform the instrumentation layer that the task has stopped */
+
+ sched_note_stop(tcb);
+
+ /* Flush all streams (File descriptors will be closed when
+ * the TCB is deallocated).
+ */
+
+#if CONFIG_NFILE_STREAMS > 0
+ (void)lib_flushall(tcb->streams);
+#endif
+
+ /* Deallocate anything left in the TCB's queues */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ sig_cleanup(tcb); /* Deallocate Signal lists */
+#endif
+
+ /* Wakeup any tasks waiting for this task to exit */
+
+#ifdef CONFIG_SCHED_WAITPID /* Experimental */
+ while (tcb->exitsem.semcount < 0)
+ {
+ /* "If more than one thread is suspended in waitpid() awaiting
+ * termination of the same process, exactly one thread will return
+ * the process status at the time of the target process termination."
+ * Hmmm.. what do we return to the others?
+ */
+
+ if (tcb->stat_loc)
+ {
+ *tcb->stat_loc = status << 8;
+ tcb->stat_loc = NULL;
+ }
+
+ /* Wake up the thread */
+
+ sem_post(&tcb->exitsem);
+ }
+#endif
+
+ /* If an exit function was registered, call it now. NOTE: In the case
+ * of task_delete(), the exit function will *not* be called on the thread
+ * execution of the task being deleted!
+ */
+
+#ifdef CONFIG_SCHED_ATEXIT
+ if (tcb->exitfunc)
+ {
+ (*tcb->exitfunc)();
+ }
+#endif
+}