summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 22:51:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 22:51:20 +0000
commit72a312c24a6e1c84bc9c9ce850f83c9b01b1b390 (patch)
tree7b8798b99a8b739606c805b7839f4351670dfbf1 /nuttx
parentf0e320ceb9ba49bc6133547e25c520c2155b38d7 (diff)
downloadpx4-nuttx-72a312c24a6e1c84bc9c9ce850f83c9b01b1b390.tar.gz
px4-nuttx-72a312c24a6e1c84bc9c9ce850f83c9b01b1b390.tar.bz2
px4-nuttx-72a312c24a6e1c84bc9c9ce850f83c9b01b1b390.zip
Fix some early z180 compile errors
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5430 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/z80/include/z180/chip.h2
-rw-r--r--nuttx/arch/z80/src/z180/switch.h13
-rw-r--r--nuttx/arch/z80/src/z180/z180_head.asm4
-rw-r--r--nuttx/arch/z80/src/z180/z180_irq.c8
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.c20
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.h16
-rw-r--r--nuttx/configs/p112/ostest/defconfig4
-rw-r--r--nuttx/include/debug.h25
-rw-r--r--nuttx/include/nuttx/compiler.h2
-rw-r--r--nuttx/mm/mm_graninit.c1
10 files changed, 54 insertions, 41 deletions
diff --git a/nuttx/arch/z80/include/z180/chip.h b/nuttx/arch/z80/include/z180/chip.h
index 22a3cee37..3844b2800 100644
--- a/nuttx/arch/z80/include/z180/chip.h
+++ b/nuttx/arch/z80/include/z180/chip.h
@@ -402,7 +402,7 @@
defined(CONFIG_ARCH_CHIP_Z8S18010PSG) || /* 64-pin DIP 10MHz 5V */ \
defined(CONFIG_ARCH_CHIP_Z8S18020FEG) || \
defined(CONFIG_ARCH_CHIP_Z8S18010PEG) || \
- defined(CONFIG_ARCH_CHIP_Z8S18010FEG
+ defined(CONFIG_ARCH_CHIP_Z8S18010FEG)
# define HAVE_Z8S180 1 /* Uses Z8S180 (5V) or Z8L180 (3.3V) core */
# define HAVE ROM 0 /* No on-chip ROM */
diff --git a/nuttx/arch/z80/src/z180/switch.h b/nuttx/arch/z80/src/z180/switch.h
index aa33bd1e1..ae80f4f76 100644
--- a/nuttx/arch/z80/src/z180/switch.h
+++ b/nuttx/arch/z80/src/z180/switch.h
@@ -42,7 +42,9 @@
************************************************************************************/
#include <nuttx/sched.h>
+
#include <nuttx/arch.h>
+#include <arch/io.h>
#include "z180_iomap.h"
#include "up_internal.h"
@@ -112,13 +114,14 @@
current_regs = savestate; \
if (current_regs) \
{ \
- current_cbr = savecbr; \
+ current_cbr = savecbr; \
} \
else \
{ \
outp(Z180_MMU_CBR, savecbr); \
} \
- }
+ } \
+ while (0)
/* The following macro is used to sample the interrupt state (as a opaque handle) */
@@ -135,9 +138,9 @@
#define SET_IRQCONTEXT(tcb) \
do \
{ \
- if ((tcb)->xcp.cbr.cbr) \
+ if ((tcb)->xcp.cbr) \
{ \
- current_cbr = (tcb)->xcp.cbr->cbr); \
+ current_cbr = (tcb)->xcp.cbr->cbr; \
} \
z180_copystate((FAR chipreg_t*)current_regs, (tcb)->xcp.regs); \
} \
@@ -157,7 +160,7 @@
#define RESTORE_USERCONTEXT(tcb) \
do \
{ \
- if ((tcb)->xcp.cbr.cbr) \
+ if ((tcb)->xcp.cbr) \
{ \
outp(Z180_MMU_CBR, (tcb)->xcp.cbr->cbr); \
} \
diff --git a/nuttx/arch/z80/src/z180/z180_head.asm b/nuttx/arch/z80/src/z180/z180_head.asm
index ddd0283e9..cb370ffda 100644
--- a/nuttx/arch/z80/src/z180/z180_head.asm
+++ b/nuttx/arch/z80/src/z180/z180_head.asm
@@ -62,7 +62,7 @@
.globl _os_start ; OS entry point
.globl _up_doirq ; Interrupt decoding logic
- .globl z180_mmu_lowinit ; MMU initialization logic
+ .globl _z180_mmu_lowinit ; MMU initialization logic
;**************************************************************************
; Reset entry point
@@ -172,7 +172,7 @@ _up_reset:
; Configure the MMU so that things will lie at the addresses that we
; expect them to
- call z180_mmu_lowinit ; Initialize the MMU
+ call _z180_mmu_lowinit ; Initialize the MMU
; Performed initialization unique to the SDCC toolchain
diff --git a/nuttx/arch/z80/src/z180/z180_irq.c b/nuttx/arch/z80/src/z180/z180_irq.c
index 929f38d6a..d5d625b33 100644
--- a/nuttx/arch/z80/src/z180/z180_irq.c
+++ b/nuttx/arch/z80/src/z180/z180_irq.c
@@ -58,6 +58,14 @@
volatile chipreg_t *current_regs;
+/* This holds the value of the MMU's CBR register. This value is set to the
+ * interrupted tasks's CBR on interrupt entry, changed to the new task's CBR if
+ * an interrrupt level context switch occurs, and restored on interrupt exit. In
+ * this way, the CBR is always correct on interrupt exit.
+ */
+
+uint8_t current_cbr;
+
/****************************************************************************
* Private Data
****************************************************************************/
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.c b/nuttx/arch/z80/src/z180/z180_mmu.c
index 076d91bef..e24b22b8e 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.c
+++ b/nuttx/arch/z80/src/z180/z180_mmu.c
@@ -41,8 +41,15 @@
#include <nuttx/config.h>
-#include <nuttx/gram.h>
+#include <errno.h>
+#include <debug.h>
+#include <nuttx/gran.h>
+
+#include <arch/irq.h>
+#include <arch/io.h>
+
+#include "up_internal.h"
#include "z180_mmu.h"
/****************************************************************************
@@ -223,7 +230,7 @@ int up_addrenv_create(FAR _TCB *tcb, size_t envsize)
{
sdbg("ERROR: No free CBR structures\n");
ret = -ENOMEM;
- goto errout_with_irq
+ goto errout_with_irq;
}
/* Now allocate the physical memory to back up the address environment */
@@ -297,7 +304,7 @@ int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb)
* copy in the child thread's TCB.
*/
- ptcb->xcp.cbr.crefs++;
+ ptcb->xcp.cbr->crefs++;
ctcb->xcp.cbr = ptcb->xcp.cbr;
}
@@ -333,7 +340,7 @@ FAR void *up_addrenv_instantiate(FAR _TCB *tcb)
/* Get the current CBR value from the CBR register */
flags = irqsave();
- cbr = inp(Z180_MMU_CBR);
+ oldcbr = inp(Z180_MMU_CBR);
/* Check if the task has an address environment. */
@@ -341,11 +348,11 @@ FAR void *up_addrenv_instantiate(FAR _TCB *tcb)
{
/* Yes.. Write the new CBR value into CBR register */
- outp(Z180_MMU_CBR, tcb->xcp.cbr.cbr);
+ outp(Z180_MMU_CBR, tcb->xcp.cbr->cbr);
}
irqrestore(flags);
- return (FAR void *)cbr;
+ return (FAR void *)oldcbr;
}
/****************************************************************************
@@ -368,6 +375,7 @@ int up_addrenv_restore(FAR void *handle)
/* Restore the CBR value */
outp(Z180_MMU_CBR, (uint8_t)handle);
+ return OK;
}
/****************************************************************************
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.h b/nuttx/arch/z80/src/z180/z180_mmu.h
index 74463427a..69ee13cc5 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.h
+++ b/nuttx/arch/z80/src/z180/z180_mmu.h
@@ -109,12 +109,10 @@
/* MMU register values */
-#define Z180_CBAR_VALUE \
- ((((CONFIG_Z180_BANKAREA_VIRTBASE >> 12) & 0x0f) << CBAR_BA_SHIFT) \
- (((CONFIG_Z180_COMMON1AREA_VIRTBASE >> 12) & 0x0f) << CBAR_CA_SHIFT))
-
-#define Z180_BBR_VALUE \
- ((CONFIG_Z180_BANKAREA_PHYSBASE >> 12) & 0xff)
+#define Z180_CBAR_BA_VALUE (((CONFIG_Z180_BANKAREA_VIRTBASE >> 12) & 0x0f) << CBAR_BA_SHIFT)
+#define Z180_CBAR_CA_VALUE (((CONFIG_Z180_COMMON1AREA_VIRTBASE >> 12) & 0x0f) << CBAR_CA_SHIFT)
+#define Z180_CBAR_VALUE (Z180_CBAR_BA_VALUE | Z180_CBAR_CA_VALUE)
+#define Z180_BBR_VALUE ((CONFIG_Z180_BANKAREA_PHYSBASE >> 12) & 0xff)
/****************************************************************************
* Public Functions
@@ -139,11 +137,11 @@ void z180_mmu_lowinit(void) __naked;
* Name: up_mmuinit
*
* Description:
- * Perform higher level initializatin of the MMU and physical memory
- * memory management logic.
+ * Perform higher level initialization of the MMU and physical memory
+ * memory management logic. More correctly prototypes in up_internal.h.
*
****************************************************************************/
-void up_mmuinit(void);
+int up_mmuinit(void);
#endif /* __ARCH_Z80_SRC_Z180_Z180_MMU_H */
diff --git a/nuttx/configs/p112/ostest/defconfig b/nuttx/configs/p112/ostest/defconfig
index 2cdc13ba5..62162f37e 100644
--- a/nuttx/configs/p112/ostest/defconfig
+++ b/nuttx/configs/p112/ostest/defconfig
@@ -332,7 +332,9 @@ CONFIG_MM_REGIONS=1
CONFIG_ARCH_HAVE_HEAP2=y
CONFIG_HEAP2_BASE=0x00000000
CONFIG_HEAP2_SIZE=0
-# CONFIG_GRAN is not set
+CONFIG_GRAN=y
+CONFIG_GRAN_SINGLE=y
+# CONFIG_GRAN_INTR is not set
#
# Binary Formats
diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h
index 1f8c7d7ca..aa5efd432 100644
--- a/nuttx/include/debug.h
+++ b/nuttx/include/debug.h
@@ -571,12 +571,9 @@
* Public Function Prototypes
****************************************************************************/
-#undef EXTERN
#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/* These low-level debug APIs are provided by the NuttX library. If the
@@ -585,21 +582,20 @@ extern "C" {
* or the other of the following.
*/
-EXTERN int lib_rawprintf(FAR const char *format, ...);
+int lib_rawprintf(FAR const char *format, ...);
#ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int lib_lowprintf(FAR const char *format, ...);
+int lib_lowprintf(FAR const char *format, ...);
#endif
/* Dump a buffer of data */
-EXTERN void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer,
- unsigned int buflen);
+void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen);
/* Enable or disable debug output */
#ifdef CONFIG_DEBUG_ENABLE
-EXTERN void dbg_enable(bool enable);
+void dbg_enable(bool enable);
#endif
/* If the cross-compiler's pre-processor does not support variable length
@@ -608,23 +604,22 @@ EXTERN void dbg_enable(bool enable);
#ifndef CONFIG_CPP_HAVE_VARARGS
#ifdef CONFIG_DEBUG
-EXTERN int dbg(const char *format, ...);
+int dbg(const char *format, ...);
# ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int lldbg(const char *format, ...);
+int lldbg(const char *format, ...);
# endif
# ifdef CONFIG_DEBUG_VERBOSE
-EXTERN int vdbg(const char *format, ...);
+int vdbg(const char *format, ...);
# ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int llvdbg(const char *format, ...);
+int llvdbg(const char *format, ...);
# endif
#endif
#endif /* CONFIG_DEBUG */
#endif /* CONFIG_CPP_HAVE_VARARGS */
-#undef EXTERN
#if defined(__cplusplus)
}
#endif
diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h
index f700e539d..091e66765 100644
--- a/nuttx/include/nuttx/compiler.h
+++ b/nuttx/include/nuttx/compiler.h
@@ -262,7 +262,7 @@
* external RAM.
*/
-#if defined(__z80) || defined(__gbz80)
+#if defined(__SDCC_z80) || defined(__SDCC_z180) || defined(__SDCC_gbz80)
# define FAR
# define NEAR
# define CODE
diff --git a/nuttx/mm/mm_graninit.c b/nuttx/mm/mm_graninit.c
index 54b729988..8f811c65f 100644
--- a/nuttx/mm/mm_graninit.c
+++ b/nuttx/mm/mm_graninit.c
@@ -206,7 +206,6 @@ gran_common_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran,
#ifdef CONFIG_GRAN_SINGLE
int gran_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran,
uint8_t log2align)
-int gran_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gran)
{
g_graninfo = gran_common_initialize(heapstart, heapsize, log2gran,
log2align);