summaryrefslogtreecommitdiff
path: root/nuttx/arch/hc
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-04 19:43:10 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-04 19:43:10 +0000
commit244faa4df19e834ea16718e646f4c337a2b47165 (patch)
tree84ea33eedd9008f0e2a62f05d08decb2feeef9a5 /nuttx/arch/hc
parente6e92a686b35f50455f9a6c1be6e59c110e91b93 (diff)
downloadpx4-nuttx-244faa4df19e834ea16718e646f4c337a2b47165.tar.gz
px4-nuttx-244faa4df19e834ea16718e646f4c337a2b47165.tar.bz2
px4-nuttx-244faa4df19e834ea16718e646f4c337a2b47165.zip
Add HC12 header files
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2304 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/hc')
-rwxr-xr-xnuttx/arch/hc/include/arch.h81
-rwxr-xr-xnuttx/arch/hc/include/hc12/limits.h86
-rwxr-xr-xnuttx/arch/hc/include/hc12/types.h96
-rwxr-xr-xnuttx/arch/hc/include/limits.h53
-rwxr-xr-xnuttx/arch/hc/include/types.h65
-rwxr-xr-xnuttx/arch/hc/src/common/up_arch.h92
-rwxr-xr-xnuttx/arch/hc/src/common/up_modifyreg16.c85
-rwxr-xr-xnuttx/arch/hc/src/common/up_modifyreg32.c85
-rwxr-xr-xnuttx/arch/hc/src/common/up_modifyreg8.c85
9 files changed, 728 insertions, 0 deletions
diff --git a/nuttx/arch/hc/include/arch.h b/nuttx/arch/hc/include/arch.h
new file mode 100755
index 000000000..980d5517a
--- /dev/null
+++ b/nuttx/arch/hc/include/arch.h
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/hc/include/arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/arch.h
+ */
+
+#ifndef __ARCH_HC_INCLUDE_ARCH_H
+#define __ARCH_HC_INCLUDE_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ARCH_HC_INCLUDE_ARCH_H */
diff --git a/nuttx/arch/hc/include/hc12/limits.h b/nuttx/arch/hc/include/hc12/limits.h
new file mode 100755
index 000000000..3d4206e2a
--- /dev/null
+++ b/nuttx/arch/hc/include/hc12/limits.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/hc/include/hc12/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_HC_INCLUDE_HC12_LIMITS_H
+#define __ARCH_HC_INCLUDE_HC12_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN 0x80
+#define SCHAR_MAX 0x7f
+#define UCHAR_MAX 0xff
+
+/* These could be different on machines where char is unsigned */
+
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+
+#define SHRT_MIN 0x8000
+#define SHRT_MAX 0x7fff
+#define USHRT_MAX 0xffff
+
+/* The size of an integer is controlled with the -mshort or -mnoshort GCC
+ * options. Here we assume that -mshort is applied and that the size of
+ * and integer is 2-bytes (unless CONFIG_HC12_INT32 is defined)
+ */
+
+#ifdef CONFIG_HC12_INT32
+# define INT_MIN 0x80000000
+# define INT_MAX 0x7fffffff
+# define UINT_MAX 0xffffffff
+#else
+# define INT_MIN 0x8000
+# define INT_MAX 0x7fff
+# define UINT_MAX 0xffff
+#endif
+
+/* Long is 4-bytes and long long is 8 bytes in any case */
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#define LLONG_MAX 0x8000000000000000
+#define LLONG_MIN 0x7fffffffffffffff
+#define ULLONG_MAX 0xffffffffffffffff
+
+#endif /* __ARCH_HC_INCLUDE_HC12_LIMITS_H */
diff --git a/nuttx/arch/hc/include/hc12/types.h b/nuttx/arch/hc/include/hc12/types.h
new file mode 100755
index 000000000..4eb006c3c
--- /dev/null
+++ b/nuttx/arch/hc/include/hc12/types.h
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * arch/hc/include/hc12/types.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARCH_HC_INCLUDE_HC12_TYPES_H
+#define __ARCH_HC_INCLUDE_HC12_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard GNU types */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef short sint16;
+typedef unsigned short uint16;
+
+/* Normally, mc68hc1x code is compiled with the -mshort option
+ * which results in a 16-bit integer. If -mnoshort is defined
+ * then an integer is 32-bits. GCC will defined __INT__ accordingly:
+ */
+
+# if __INT__ == 16
+typedef long sint32;
+typedef unsigned long uint32;
+#else
+typedef int sint32;
+typedef unsigned int uint32;
+#endif
+
+typedef long long sint64;
+typedef unsigned long long uint64;
+
+/* A pointer is two bytes */
+
+typedef unsigned short uintptr;
+
+/* This is the size of the interrupt state save returned by irqsave()*/
+
+typedef unsigned int irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_HC_INCLUDE_HC12_TYPES_H */
diff --git a/nuttx/arch/hc/include/limits.h b/nuttx/arch/hc/include/limits.h
new file mode 100755
index 000000000..fb74bf1b3
--- /dev/null
+++ b/nuttx/arch/hc/include/limits.h
@@ -0,0 +1,53 @@
+/****************************************************************************
+ * arch/hc/include/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_HC_INCLUDE_LIMITS_H
+#define __ARCH_HC_INCLUDE_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Include architecture-specific limits definitions */
+
+#ifdef CONFIG_ARCH_HC12
+# include <arch/hc12/limits.h>
+#endif
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#endif /* __ARCH_HC_INCLUDE_LIMITS_H */
diff --git a/nuttx/arch/hc/include/types.h b/nuttx/arch/hc/include/types.h
new file mode 100755
index 000000000..938d7fc52
--- /dev/null
+++ b/nuttx/arch/hc/include/types.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ * arch/hc/include/types.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARCH_HC_INCLUDE_TYPES_H
+#define __ARCH_HC_INCLUDE_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Include architecture-specific limits definitions */
+
+#ifdef CONFIG_ARCH_HC12
+# include <arch/hc12/types.h>
+#endif
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_HC_INCLUDE_TYPES_H */
diff --git a/nuttx/arch/hc/src/common/up_arch.h b/nuttx/arch/hc/src/common/up_arch.h
new file mode 100755
index 000000000..8234148a2
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_arch.h
@@ -0,0 +1,92 @@
+/****************************************************************************
+ * arch/hc/src/common/up_arch.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef ___ARCH_HC_SRC_COMMON_UP_ARCH_H
+#define ___ARCH_HC_SRC_COMMON_UP_ARCH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <sys/types.h>
+#endif
+
+#include <arch/board/board.h>
+#include "chip.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+# define getreg8(a) (*(volatile ubyte *)(a))
+# define putreg8(v,a) (*(volatile ubyte *)(a) = (v))
+# define getreg16(a) (*(volatile uint16 *)(a))
+# define putreg16(v,a) (*(volatile uint16 *)(a) = (v))
+# define getreg32(a) (*(volatile uint32 *)(a))
+# define putreg32(v,a) (*(volatile uint32 *)(a) = (v))
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Atomic modification of registers */
+
+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_HC_SRC_COMMON_UP_ARCH_H */
diff --git a/nuttx/arch/hc/src/common/up_modifyreg16.c b/nuttx/arch/hc/src/common/up_modifyreg16.c
new file mode 100755
index 000000000..2774d309d
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_modifyreg16.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/hc/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/hc/src/common/up_modifyreg32.c b/nuttx/arch/hc/src/common/up_modifyreg32.c
new file mode 100755
index 000000000..f846c835e
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_modifyreg32.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/hc/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/hc/src/common/up_modifyreg8.c b/nuttx/arch/hc/src/common/up_modifyreg8.c
new file mode 100755
index 000000000..3f6f8b4f5
--- /dev/null
+++ b/nuttx/arch/hc/src/common/up_modifyreg8.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * arch/hc/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);
+}