summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/common/up_arch.h23
-rw-r--r--nuttx/arch/arm/src/common/up_cache.S24
-rw-r--r--nuttx/arch/arm/src/common/up_fullcontextrestore.S4
-rw-r--r--nuttx/arch/arm/src/common/up_modifyreg16.c85
-rw-r--r--nuttx/arch/arm/src/common/up_modifyreg32.c85
-rw-r--r--nuttx/arch/arm/src/common/up_modifyreg8.c85
-rw-r--r--nuttx/arch/arm/src/common/up_nommuhead.S20
-rw-r--r--nuttx/arch/arm/src/common/up_saveusercontext.S4
-rw-r--r--nuttx/arch/arm/src/common/up_vectortab.S28
-rw-r--r--nuttx/arch/arm/src/lm3s/Make.defs3
10 files changed, 317 insertions, 44 deletions
diff --git a/nuttx/arch/arm/src/common/up_arch.h b/nuttx/arch/arm/src/common/up_arch.h
index 1ad0381ed..71a33bb3e 100644
--- a/nuttx/arch/arm/src/common/up_arch.h
+++ b/nuttx/arch/arm/src/common/up_arch.h
@@ -82,11 +82,28 @@ static inline void putreg16(uint16 val, unsigned int addr)
__asm__ __volatile__("\tstrh %0, [%1]\n\t": : "r"(val), "r"(addr));
}
-/* Most DM320 registers are 16-bits wide */
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Atomic modification of registers */
-#define getreg(a) getreg16(a)
-#define putreg(v,a) putreg16(v,a)
+EXTERN void modifyreg8(unsigned int addr, ubyte clearbits, ubyte setbits);
+EXTERN void modifyreg16(unsigned int addr, uint16 clearbits, uint16 setbits);
+EXTERN void modifyreg32(unsigned int addr, uint32 clearbits, uint32 setbits);
+#undef EXTERN
+#if defined(__cplusplus)
+}
#endif
+#endif /* __ASSEMBLY__ */
#endif /* ___ARCH_ARM_SRC_COMMON_UP_ARCH_H */
diff --git a/nuttx/arch/arm/src/common/up_cache.S b/nuttx/arch/arm/src/common/up_cache.S
index 5e6f6610b..571217f0e 100644
--- a/nuttx/arch/arm/src/common/up_cache.S
+++ b/nuttx/arch/arm/src/common/up_cache.S
@@ -1,7 +1,7 @@
-/********************************************************************
+/****************************************************************************
* common/up_cache.S
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,29 +31,29 @@
* 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 "up_internal.h"
#include "up_arch.h"
-/********************************************************************
+/****************************************************************************
* Definitions
- ********************************************************************/
+ ****************************************************************************/
#define CACHE_DLINESIZE 32
-/********************************************************************
+/****************************************************************************
* Assembly Macros
- ********************************************************************/
+ ****************************************************************************/
-/**************************************************************************
+/****************************************************************************
* Name: up_flushicache
- **************************************************************************/
+ ****************************************************************************/
/* Esure coherency between the Icache and the Dcache in the region described
* by r0=start and r1=end.
diff --git a/nuttx/arch/arm/src/common/up_fullcontextrestore.S b/nuttx/arch/arm/src/common/up_fullcontextrestore.S
index 21529e6aa..43dcf6573 100644
--- a/nuttx/arch/arm/src/common/up_fullcontextrestore.S
+++ b/nuttx/arch/arm/src/common/up_fullcontextrestore.S
@@ -1,7 +1,7 @@
/**************************************************************************
* common/up_fullcontextrestore.S
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
diff --git a/nuttx/arch/arm/src/common/up_modifyreg16.c b/nuttx/arch/arm/src/common/up_modifyreg16.c
new file mode 100644
index 000000000..2c235ebfe
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_modifyreg16.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/arm/src/common/up_modifyreg16.c
+ *
+ * Copyright (C) 2009 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 <sys/types.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg16
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg16(unsigned int addr, uint16 clearbits, uint16 setbits)
+{
+ irqstate_t flags;
+ uint16 regval;
+
+ flags = irqsave();
+ regval = getreg16(addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg16(regval, addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/arm/src/common/up_modifyreg32.c b/nuttx/arch/arm/src/common/up_modifyreg32.c
new file mode 100644
index 000000000..33b40ae3a
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_modifyreg32.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/arm/src/common/up_modifyreg32.c
+ *
+ * Copyright (C) 2009 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 <sys/types.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg32
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg32(unsigned int addr, uint32 clearbits, uint32 setbits)
+{
+ irqstate_t flags;
+ uint32 regval;
+
+ flags = irqsave();
+ regval = getreg32(addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg32(regval, addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/arm/src/common/up_modifyreg8.c b/nuttx/arch/arm/src/common/up_modifyreg8.c
new file mode 100644
index 000000000..eefce6db0
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_modifyreg8.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/arm/src/common/up_modifyreg8.c
+ *
+ * Copyright (C) 2009 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 <sys/types.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: modifyreg8
+ *
+ * Description:
+ * Atomically modify the specified bits in a memory mapped register
+ *
+ ****************************************************************************/
+
+void modifyreg8(unsigned int addr, ubyte clearbits, ubyte setbits)
+{
+ irqstate_t flags;
+ ubyte regval;
+
+ flags = irqsave();
+ regval = getreg8(addr);
+ regval &= ~clearbits;
+ regval |= setbits;
+ putreg8(regval, addr);
+ irqrestore(flags);
+}
diff --git a/nuttx/arch/arm/src/common/up_nommuhead.S b/nuttx/arch/arm/src/common/up_nommuhead.S
index 36638c6ae..e6ff048bb 100644
--- a/nuttx/arch/arm/src/common/up_nommuhead.S
+++ b/nuttx/arch/arm/src/common/up_nommuhead.S
@@ -1,7 +1,7 @@
-/********************************************************************
+/****************************************************************************
* common/up_nommuhead.S
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,19 +31,19 @@
* 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 "up_internal.h"
#include "up_arch.h"
-/********************************************************************
+/****************************************************************************
* Macros
- ********************************************************************/
+ ****************************************************************************/
/* This macro will modify r0, r1, r2 and r14 */
@@ -57,9 +57,9 @@
.endm
#endif
-/********************************************************************
+/****************************************************************************
* OS Entry Point
- ********************************************************************/
+ ****************************************************************************/
/* We assume the bootloader has already initialized most of the h/w for
* us and that only leaves us having to do some os specific things
diff --git a/nuttx/arch/arm/src/common/up_saveusercontext.S b/nuttx/arch/arm/src/common/up_saveusercontext.S
index cdaf7cc25..dfae477c4 100644
--- a/nuttx/arch/arm/src/common/up_saveusercontext.S
+++ b/nuttx/arch/arm/src/common/up_saveusercontext.S
@@ -1,7 +1,7 @@
/**************************************************************************
* common/up_saveusercontext.S
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
diff --git a/nuttx/arch/arm/src/common/up_vectortab.S b/nuttx/arch/arm/src/common/up_vectortab.S
index dc7c38c61..0fad04ad6 100644
--- a/nuttx/arch/arm/src/common/up_vectortab.S
+++ b/nuttx/arch/arm/src/common/up_vectortab.S
@@ -1,7 +1,7 @@
-/********************************************************************
+/****************************************************************************
* common/up_vectortab.S
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,32 +31,32 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ********************************************************************/
+ ****************************************************************************/
-/********************************************************************
+/****************************************************************************
* Included Files
- ********************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
-/********************************************************************
+/****************************************************************************
* Definitions
- ********************************************************************/
+ ****************************************************************************/
-/********************************************************************
+/****************************************************************************
* Global Data
- ********************************************************************/
+ ****************************************************************************/
-/********************************************************************
+/****************************************************************************
* Assembly Macros
- ********************************************************************/
+ ****************************************************************************/
-/********************************************************************
+/****************************************************************************
* Name: _vector_start
*
* Description:
* Vector initialization block
- ********************************************************************/
+ ****************************************************************************/
.globl _vector_start
diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs
index cf72f460b..3115927a7 100644
--- a/nuttx/arch/arm/src/lm3s/Make.defs
+++ b/nuttx/arch/arm/src/lm3s/Make.defs
@@ -42,7 +42,8 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \
up_prefetchabort.c up_releasepending.c up_releasestack.c \
up_reprioritizertr.c up_schedulesigaction.c \
up_sigdeliver.c up_syscall.c up_unblocktask.c \
- up_undefinedinsn.c up_usestack.c
+ up_undefinedinsn.c up_usestack.c \
+ up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
CHIP_ASRCS =
CHIP_CSRCS =