summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-11 19:16:45 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-02-11 19:16:45 +0000
commit86afffb7b3441d1ac33e5b82136bd58c3b0e8a97 (patch)
tree879ef02330adbf6a1dcd976cc90f649250592034 /nuttx/arch/z80/include
parentc57406e92f257c877a7dc8e9a8bfd21693f12b5c (diff)
downloadpx4-nuttx-86afffb7b3441d1ac33e5b82136bd58c3b0e8a97.tar.gz
px4-nuttx-86afffb7b3441d1ac33e5b82136bd58c3b0e8a97.tar.bz2
px4-nuttx-86afffb7b3441d1ac33e5b82136bd58c3b0e8a97.zip
Changes for Z8Encore\! compile
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@668 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z80/include')
-rw-r--r--nuttx/arch/z80/include/types.h34
-rw-r--r--nuttx/arch/z80/include/z8/irq.h17
-rw-r--r--nuttx/arch/z80/include/z8/types.h93
-rw-r--r--nuttx/arch/z80/include/z80/irq.h2
-rw-r--r--nuttx/arch/z80/include/z80/types.h86
5 files changed, 197 insertions, 35 deletions
diff --git a/nuttx/arch/z80/include/types.h b/nuttx/arch/z80/include/types.h
index ade00123a..5e1a3c42d 100644
--- a/nuttx/arch/z80/include/types.h
+++ b/nuttx/arch/z80/include/types.h
@@ -33,8 +33,8 @@
*
****************************************************************************/
-/* This file should never be included directed but, rather,
- * only indirectly through sys/types.h
+/* This file should never be included directed but, rather, only indirectly
+* through sys/types.h
*/
#ifndef __ARCH_TYPES_H
@@ -44,6 +44,8 @@
* Included Files
****************************************************************************/
+#include <arch/chip/types.h>
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -52,34 +54,6 @@
* Type Declarations
****************************************************************************/
-#ifndef __ASSEMBLY__
-
-/* These are the sizes of the standard SDCC types
- *
- * For SDCC, sizeof(int) is 16 and sizeof(long) is 32.
- * long long and double are not supported.
- *
- * Generic pointers are 3 bytes in length with the the
- * first byte holding data space intformation.
- */
-
-typedef char sbyte;
-typedef unsigned char ubyte;
-typedef unsigned char uint8;
-typedef unsigned char boolean;
-typedef int sint16;
-typedef unsigned int uint16;
-typedef long sint32;
-typedef unsigned long uint32;
-
-/* This is the size of the interrupt state save returned by
- * irqsave()
- */
-
-typedef uint16 irqstate_t;
-
-#endif /* __ASSEMBLY__ */
-
/****************************************************************************
* Global Function Prototypes
****************************************************************************/
diff --git a/nuttx/arch/z80/include/z8/irq.h b/nuttx/arch/z80/include/z8/irq.h
index 91a5ffd1c..27ea9f1c9 100644
--- a/nuttx/arch/z80/include/z8/irq.h
+++ b/nuttx/arch/z80/include/z8/irq.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/z8/irq.h
+ * arch/z8/include/z8/irq.h
* arch/chip/irq.h
*
* Copyright (C) 2008 Gregory Nutt. All rights reserved.
@@ -82,6 +82,18 @@
#define XCPTCONTEXT_REGS (9)
#define XCPTCONTEXT_SIZE (2 * XCPTCONTEXT_REGS)
+/* The ZDS-II provides built-in operations to test & disable and to restore
+ * the interrupt state.
+ *
+ * irqstate_t irqsave(void);
+ * void irqrestore(irqstate_t flags);
+ */
+
+#ifdef __ZILOG__
+# define irqsave() TDI()
+# define irqrestore(f) RI(f)
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -135,9 +147,6 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN irqstate_t irqsave(void) __naked;
-EXTERN void irqrestore(irqstate_t flags) __naked;
-
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/arch/z80/include/z8/types.h b/nuttx/arch/z80/include/z8/types.h
new file mode 100644
index 000000000..97cb72d98
--- /dev/null
+++ b/nuttx/arch/z80/include/z8/types.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ * arch/z80/include/z8/types.h
+ * include/arch/chip/types.h
+ *
+ * Copyright (C) 2008 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 Gregory Nutt 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_CHIP_TYPES_H
+#define __ARCH_CHIP_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the types supported by the ZiLOG Z8Encore! compiler:
+ *
+ * int - 16-bits
+ * short - 16-bits
+ * long - 32-bits
+ * char - 8-bits
+ * float - 32-bits
+ * double - 32-bits
+ *
+ * Pointers:
+ *
+ * near pointer - 8-bits
+ * far pointer - 16-bits
+ * rom pointer - 16-bits
+ */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef int sint16;
+typedef unsigned int uint16;
+typedef long sint32;
+typedef unsigned long uint32;
+
+/* This is the size of the interrupt state save returned by irqsave() */
+
+typedef uint16 irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_CHIP_TYPES_H */
diff --git a/nuttx/arch/z80/include/z80/irq.h b/nuttx/arch/z80/include/z80/irq.h
index 86bdfd273..f71ed208e 100644
--- a/nuttx/arch/z80/include/z80/irq.h
+++ b/nuttx/arch/z80/include/z80/irq.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/z80/irq.h
+ * arch/z80/include/z80/irq.h
* arch/chip/irq.h
*
* Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
diff --git a/nuttx/arch/z80/include/z80/types.h b/nuttx/arch/z80/include/z80/types.h
new file mode 100644
index 000000000..97efa0761
--- /dev/null
+++ b/nuttx/arch/z80/include/z80/types.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/z80/include/z80/types.h
+ * include/arch/chip/types.h
+ *
+ * Copyright (C) 2007, 2008 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 Gregory Nutt 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_CHIP_TYPES_H
+#define __ARCH_CHIP_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard SDCC types
+ *
+ * For SDCC, sizeof(int) is 16 and sizeof(long) is 32. long long and double
+ * are not supported.
+ *
+ * Generic pointers are 3 bytes in length with the first byte holding data
+ * space information.
+ */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef int sint16;
+typedef unsigned int uint16;
+typedef long sint32;
+typedef unsigned long uint32;
+
+/* This is the size of the interrupt state save returned by irqsave() */
+
+typedef uint16 irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_CHIP_TYPES_H */