summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/armv7-m/exc_return.h15
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c18
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c18
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.c2
-rw-r--r--nuttx/configs/open1788/scripts/memory.ld3
-rw-r--r--nuttx/configs/sam3u-ek/scripts/memory.ld105
-rw-r--r--nuttx/include/stdlib.h6
-rw-r--r--nuttx/libc/stdlib/Make.defs4
-rw-r--r--nuttx/libc/stdlib/lib_itoa.c85
9 files changed, 159 insertions, 97 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/exc_return.h b/nuttx/arch/arm/src/armv7-m/exc_return.h
index a7840d5c3..5f46dd071 100644
--- a/nuttx/arch/arm/src/armv7-m/exc_return.h
+++ b/nuttx/arch/arm/src/armv7-m/exc_return.h
@@ -93,13 +93,24 @@
* state from the main stack. Execution uses MSP after return.
*/
-#define EXC_RETURN_PRIVTHR 0xfffffff9
+#if defined(CONFIG_ARMV7M_CMNVECTOR) && defined(CONFIG_ARCH_FPU)
+# define EXC_RETURN_PRIVTHR (EXC_RETURN_BASE | EXC_RETURN_THREAD_MODE)
+#else
+# define EXC_RETURN_PRIVTHR (EXC_RETURN_BASE | EXC_RETURN_STD_CONTEXT | \
+ EXC_RETURN_THREAD_MODE)
+#endif
/* EXC_RETURN_UNPRIVTHR: Return to unprivileged thread mode. Exception return gets
* state from the process stack. Execution uses PSP after return.
*/
-#define EXC_RETURN_UNPRIVTHR 0xfffffffd
+#if defined(CONFIG_ARMV7M_CMNVECTOR) && defined(CONFIG_ARCH_FPU)
+# define EXC_RETURN_UNPRIVTHR (EXC_RETURN_BASE | EXC_RETURN_THREAD_MODE | \
+ EXC_RETURN_PROCESS_STACK)
+#else
+# define EXC_RETURN_UNPRIVTHR (EXC_RETURN_BASE | EXC_RETURN_STD_CONTEXT | \
+ EXC_RETURN_THREAD_MODE | EXC_RETURN_PROCESS_STACK)
+#endif
/* In the kernel build is not selected, then all threads run in privileged thread
* mode.
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index 047edf5e3..e6eadf306 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -193,6 +193,24 @@
* If a protected kernel-space heap is provided, the kernel heap must be
* allocated (and protected) by an analogous up_allocate_kheap().
*
+ * The following memory map is assumed for the flat build:
+ *
+ * .data region. Size determined at link time.
+ * .bss region Size determined at link time.
+ * IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Heap. Extends to the end of SRAM.
+ *
+ * The following memory map is assumed for the kernel build:
+ *
+ * Kernel .data region. Size determined at link time.
+ * Kernel .bss region Size determined at link time.
+ * Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Padding for alignment
+ * User .data region. Size determined at link time.
+ * User .bss region Size determined at link time.
+ * Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE.
+ * User heap. Extends to the end of SRAM.
+ *
****************************************************************************/
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
index 576fae802..1b41812bb 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_allocateheap.c
@@ -104,6 +104,24 @@
* If a protected kernel-space heap is provided, the kernel heap must be
* allocated (and protected) by an analogous up_allocate_kheap().
*
+ * The following memory map is assumed for the flat build:
+ *
+ * .data region. Size determined at link time.
+ * .bss region Size determined at link time.
+ * IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Heap. Extends to the end of SRAM.
+ *
+ * The following memory map is assumed for the kernel build:
+ *
+ * Kernel .data region. Size determined at link time.
+ * Kernel .bss region Size determined at link time.
+ * Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
+ * Padding for alignment
+ * User .data region. Size determined at link time.
+ * User .bss region Size determined at link time.
+ * Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE.
+ * User heap. Extends to the end of SRAM.
+ *
****************************************************************************/
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 006f67142..09efaf193 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -1719,7 +1719,7 @@ static void stm32_freeframe(FAR struct stm32_ethmac_s *priv)
/* Check if this is the last segement of a TX frame */
- if ((txdesc->tdes0 & ETH_TDES0_FS) != 0)
+ if ((txdesc->tdes0 & ETH_TDES0_LS) != 0)
{
/* Yes.. Decrement the number of frames "in-flight". */
diff --git a/nuttx/configs/open1788/scripts/memory.ld b/nuttx/configs/open1788/scripts/memory.ld
index d1ae3aa6e..4f301dcfb 100644
--- a/nuttx/configs/open1788/scripts/memory.ld
+++ b/nuttx/configs/open1788/scripts/memory.ld
@@ -52,7 +52,8 @@
* ------- ---- Padded to 4KB
* 0x10000 1000: User .data region. Size is variable.
* ------- ---- User .bss region Size is variable.
- * ------- ---- Beginning of kernel heap
+ * ------- ---- Beginning of kernel heap. Size determined by
+ * CONFIG_MM_KERNEL_HEAPSIZE.
* 0x10000 8000: Beginning of user heap. Can vary with other settings.
* 0x10001 0000: End+1 of CPU RAM
*/
diff --git a/nuttx/configs/sam3u-ek/scripts/memory.ld b/nuttx/configs/sam3u-ek/scripts/memory.ld
index d187ed40c..f88c4c80b 100644
--- a/nuttx/configs/sam3u-ek/scripts/memory.ld
+++ b/nuttx/configs/sam3u-ek/scripts/memory.ld
@@ -42,7 +42,21 @@
*
* For MPU support, the kernel-mode NuttX section is assumed to be 64Kb of
* FLASH and 4Kb of SRAM. That, of course, can be optimized as needed (See
- * also configs/sam3u-ek/scripts/kernel-space.ld).
+ * also configs/open1788/scripts/kernel-space.ld). A detailed memory map
+ * for the CPU SRAM region is as follows:
+ *
+ * 0x20000 0000: Kernel .data region. Typical size: 0.1KB
+ * ------- ---- Kernel .bss region. Typical size: 1.8KB
+ * ------- ---- Kernel IDLE thread stack (approximate). Size is
+ * determined by CONFIG_IDLETHREAD_STACKSIZE and
+ * adjustments for alignment. Typical is 1KB.
+ * ------- ---- Padded to 4KB
+ * 0x20000 1000: User .data region. Size is variable.
+ * ------- ---- User .bss region Size is variable.
+ * ------- ---- Beginning of kernel heap. Size determined by
+ * CONFIG_MM_KERNEL_HEAPSIZE.
+ * ------- ---- Beginning of user heap. Can vary with other settings.
+ * 0x20000 8000: End+1 of CPU RAM
*/
MEMORY
@@ -61,92 +75,3 @@ MEMORY
sram2 (rwx) : ORIGIN = 0x20080000, LENGTH = 16K
}
-
-/* Make sure that the critical memory management functions are in user-space.
- * Currently, the plan is that the memory manager will reside in user-space
- * but be usable both by kernel- and user-space code
- */
-
-EXTERN(umm_initialize)
-EXTERN(umm_addregion)
-EXTERN(umm_trysemaphore)
-EXTERN(umm_givesemaphore)
-
-EXTERN(malloc)
-EXTERN(realloc)
-EXTERN(zalloc)
-EXTERN(free)
-
-OUTPUT_ARCH(arm)
-
-SECTIONS
-{
- .userspace : {
- *(.userspace)
- } > uflash
-
- .text : {
- _stext = ABSOLUTE(.);
- *(.vectors)
- *(.text .text.*)
- *(.fixup)
- *(.gnu.warning)
- *(.rodata .rodata.*)
- *(.gnu.linkonce.t.*)
- *(.glue_7)
- *(.glue_7t)
- *(.got)
- *(.gcc_except_table)
- *(.gnu.linkonce.r.*)
- _etext = ABSOLUTE(.);
- } > uflash
-
- .init_section : {
- _sinit = ABSOLUTE(.);
- *(.init_array .init_array.*)
- _einit = ABSOLUTE(.);
- } > uflash
-
- .ARM.extab : {
- *(.ARM.extab*)
- } > uflash
-
- __exidx_start = ABSOLUTE(.);
- .ARM.exidx : {
- *(.ARM.exidx*)
- } > uflash
- __exidx_end = ABSOLUTE(.);
-
- _eronly = ABSOLUTE(.);
-
- .data : {
- _sdata = ABSOLUTE(.);
- *(.data .data.*)
- *(.gnu.linkonce.d.*)
- CONSTRUCTORS
- _edata = ABSOLUTE(.);
- } > usram1 AT > uflash
-
- .bss : {
- _sbss = ABSOLUTE(.);
- *(.bss .bss.*)
- *(.gnu.linkonce.b.*)
- *(COMMON)
- _ebss = ABSOLUTE(.);
- } > usram1
-
- /* Stabs debugging sections. */
-
- .stab 0 : { *(.stab) }
- .stabstr 0 : { *(.stabstr) }
- .stab.excl 0 : { *(.stab.excl) }
- .stab.exclstr 0 : { *(.stab.exclstr) }
- .stab.index 0 : { *(.stab.index) }
- .stab.indexstr 0 : { *(.stab.indexstr) }
- .comment 0 : { *(.comment) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_info 0 : { *(.debug_info) }
- .debug_line 0 : { *(.debug_line) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- .debug_aranges 0 : { *(.debug_aranges) }
-}
diff --git a/nuttx/include/stdlib.h b/nuttx/include/stdlib.h
index ad4344ade..4cf0990ea 100644
--- a/nuttx/include/stdlib.h
+++ b/nuttx/include/stdlib.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/stdlib.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -157,6 +157,10 @@ double_t strtod(const char *, char **);
#endif
#define atof(nptr) strtod((nptr), NULL)
+/* Binary to string conversions */
+
+char *itoa(int value, char *str, int base);
+
/* Memory Management */
FAR void *malloc(size_t);
diff --git a/nuttx/libc/stdlib/Make.defs b/nuttx/libc/stdlib/Make.defs
index dcc4dab26..5d726ba3a 100644
--- a/nuttx/libc/stdlib/Make.defs
+++ b/nuttx/libc/stdlib/Make.defs
@@ -35,8 +35,8 @@
# Add the stdlib C files to the build
-CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_labs.c lib_llabs.c \
- lib_rand.c lib_qsort.c
+CSRCS += lib_abs.c lib_abort.c lib_imaxabs.c lib_itoa.c lib_labs.c \
+ lib_llabs.c lib_rand.c lib_qsort.c
# Add the stdlib directory to the build
diff --git a/nuttx/libc/stdlib/lib_itoa.c b/nuttx/libc/stdlib/lib_itoa.c
new file mode 100644
index 000000000..a1afeaaa8
--- /dev/null
+++ b/nuttx/libc/stdlib/lib_itoa.c
@@ -0,0 +1,85 @@
+/************************************************************************
+ * libc/stdlib/lib_itoa.c
+ *
+ * Copyright (C) 2013 Brooks Automation, Inc. All rights reserved.
+ * Author: Ryan Sundberg <ryan.sundberg@brooks.com>
+ *
+ * This file is a part of NuttX:
+ *
+ * Copyright (C) 2010-2011 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 <stdlib.h>
+
+/************************************************************************
+ * Global Functions
+ ************************************************************************/
+
+char *itoa(int val, char *str, int base)
+{
+ static const char *digits = "0123456789abcdefghijklmnopqrstuvwxyz";
+ int intval = abs(val), digit, pos, len;
+ char *buf = str;
+ char swap;
+
+ if (base >= 2 && base <= 36)
+ {
+ do
+ {
+ digit = intval % base;
+ intval = intval / base;
+ *buf++ = digits[digit];
+ }
+ while (intval > 0);
+
+ if (val < 0)
+ {
+ *buf++ = '-';
+ }
+
+ for (pos = 0, len = buf - str; pos < len / 2; pos++)
+ {
+ swap = str[len - pos - 1];
+ str[len - pos - 1] = str[pos];
+ str[pos] = swap;
+ }
+ }
+
+ *buf = '\0';
+
+ return str;
+}