summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 21:42:15 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 21:42:15 +0000
commitf0e320ceb9ba49bc6133547e25c520c2155b38d7 (patch)
treefddaccb5f325a2ab18f593609e63b46e98733620 /nuttx/arch/z80
parentcdbb7040cc2ba10d5c86fccc448660a401dad7b9 (diff)
downloadpx4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.tar.gz
px4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.tar.bz2
px4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.zip
configs/p112: Add a configuration for the Z180 P112 board
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5429 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/z80')
-rw-r--r--nuttx/arch/z80/src/common/up_doirq.c1
-rw-r--r--nuttx/arch/z80/src/common/up_initialize.c8
-rw-r--r--nuttx/arch/z80/src/common/up_internal.h6
-rw-r--r--nuttx/arch/z80/src/z180/Kconfig13
-rw-r--r--nuttx/arch/z80/src/z180/switch.h103
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.c71
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.h6
-rw-r--r--nuttx/arch/z80/src/z180/z180_registerdump.c2
8 files changed, 165 insertions, 45 deletions
diff --git a/nuttx/arch/z80/src/common/up_doirq.c b/nuttx/arch/z80/src/common/up_doirq.c
index a4bb830fd..4b57f8f7b 100644
--- a/nuttx/arch/z80/src/common/up_doirq.c
+++ b/nuttx/arch/z80/src/common/up_doirq.c
@@ -102,6 +102,7 @@ FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs)
IRQ_LEAVE(irq);
}
+
up_ledoff(LED_INIRQ);
return regs;
#endif
diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c
index 1ae927831..e0b46f7ec 100644
--- a/nuttx/arch/z80/src/common/up_initialize.c
+++ b/nuttx/arch/z80/src/common/up_initialize.c
@@ -145,6 +145,14 @@ void up_initialize(void)
up_timerinit();
#endif
+ /* Initialize the CPU for those that use it (only for the Z180). This
+ * needs to be done before any tasks are created).
+ */
+
+#if CONFIG_ADDRENV
+ (void)up_mmuinit();
+#endif
+
/* Register devices */
#if CONFIG_NFILE_DESCRIPTORS > 0
diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h
index 1989f99d0..3adb02a39 100644
--- a/nuttx/arch/z80/src/common/up_internal.h
+++ b/nuttx/arch/z80/src/common/up_internal.h
@@ -117,6 +117,12 @@ EXTERN FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs);
EXTERN void up_sigdeliver(void);
+/* Defined in CPU-specific logic (only for Z180) */
+
+#if CONFIG_ADDRENV
+int up_mmuinit(void);
+#endif
+
/* Defined in up_allocateheap.c */
#if CONFIG_MM_REGIONS > 1
diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig
index 58abbd6f2..3082e69cb 100644
--- a/nuttx/arch/z80/src/z180/Kconfig
+++ b/nuttx/arch/z80/src/z180/Kconfig
@@ -137,4 +137,17 @@ config ARCH_HAVEHEAD
Use a board-specific version of the "head" file in the
configs/<board-name>/src directory
+menu "Z180 Peripheral Support"
+
+config Z180_UART0
+ bool "UART0"
+ default n
+ select ARCH_HAVE_UART0
+
+config Z180_UART1
+ bool "UART1"
+ default n
+ select ARCH_HAVE_UART1
+
+endmenu
endif
diff --git a/nuttx/arch/z80/src/z180/switch.h b/nuttx/arch/z80/src/z180/switch.h
index 38054e4b8..aa33bd1e1 100644
--- a/nuttx/arch/z80/src/z180/switch.h
+++ b/nuttx/arch/z80/src/z180/switch.h
@@ -44,6 +44,7 @@
#include <nuttx/sched.h>
#include <nuttx/arch.h>
+#include "z180_iomap.h"
#include "up_internal.h"
/************************************************************************************
@@ -58,56 +59,116 @@
/* Initialize the IRQ state */
-#define INIT_IRQCONTEXT() current_regs = NULL
+#define INIT_IRQCONTEXT() \
+ current_regs = NULL
/* IN_INTERRUPT returns true if the system is currently operating in the interrupt
* context. IN_INTERRUPT is the inline equivalent of up_interrupt_context().
*/
-#define IN_INTERRUPT() (current_regs != NULL)
+#define IN_INTERRUPT() \
+ (current_regs != NULL)
-/* The following macro is used when the system enters interrupt handling logic */
+/* The following macro declares the variables need by IRQ_ENTER and IRQ_LEAVE.
+ * These variables are used to support nested interrupts.
+ *
+ * - savestate holds the previous value of current_state.
+ * - savecpr holds the previous value of current_cpr.
+ *
+ * TODO: I think this logic is bad... I do not thing that this will really
+ * handle nested interrupts correctly. What if we are nested and then a
+ * context switch occurs? current_regs will not be updated correctly!
+ */
#define DECL_SAVESTATE() \
- FAR chipreg_t *savestate
+ FAR chipreg_t *savestate; \
+ uint8_t savecbr;
-#define IRQ_ENTER(irq, regs) \
- do { \
- savestate = (FAR chipreg_t *)current_regs; \
- current_regs = (regs); \
- } while (0)
+/* The following macro is used when the system enters interrupt handling logic.
+ * The entry values of current_regs and current_cbr and stored in local variables.
+ * Then current_regs and current_cbr are set to the values of the interrupted
+ * task.
+ */
-/* The following macro is used when the system exits interrupt handling logic */
+#define IRQ_ENTER(irq, regs) \
+ do \
+ { \
+ savestate = (FAR chipreg_t *)current_regs; \
+ savecbr = current_cbr; \
+ current_regs = (regs); \
+ current_cbr = inp(Z180_MMU_CBR); \
+ } \
+ while (0)
+
+/* The following macro is used when the system exits interrupt handling logic.
+ * The value of current_regs is restored. If we are not processing a nested
+ * interrupt (meaning that we going to return to the user task), then also
+ * set the MMU's CBR register.
+ */
-#define IRQ_LEAVE(irq) current_regs = savestate
+#define IRQ_LEAVE(irq) \
+ do \
+ { \
+ current_regs = savestate; \
+ if (current_regs) \
+ { \
+ current_cbr = savecbr; \
+ } \
+ else \
+ { \
+ outp(Z180_MMU_CBR, savecbr); \
+ } \
+ }
/* The following macro is used to sample the interrupt state (as a opaque handle) */
-#define IRQ_STATE() (current_regs)
+#define IRQ_STATE() \
+ (current_regs)
/* Save the current IRQ context in the specified TCB */
-#define SAVE_IRQCONTEXT(tcb) z180_copystate((tcb)->xcp.regs, (FAR chipreg_t*)current_regs)
+#define SAVE_IRQCONTEXT(tcb) \
+ z180_copystate((tcb)->xcp.regs, (FAR chipreg_t*)current_regs)
/* Set the current IRQ context to the state specified in the TCB */
-#define SET_IRQCONTEXT(tcb) z180_copystate((FAR chipreg_t*)current_regs, (tcb)->xcp.regs)
+#define SET_IRQCONTEXT(tcb) \
+ do \
+ { \
+ if ((tcb)->xcp.cbr.cbr) \
+ { \
+ current_cbr = (tcb)->xcp.cbr->cbr); \
+ } \
+ z180_copystate((FAR chipreg_t*)current_regs, (tcb)->xcp.regs); \
+ } \
+ while (0)
/* Save the user context in the specified TCB. User context saves can be simpler
* because only those registers normally saved in a C called need be stored.
*/
-#define SAVE_USERCONTEXT(tcb) z180_saveusercontext((tcb)->xcp.regs)
+#define SAVE_USERCONTEXT(tcb) \
+ z180_saveusercontext((tcb)->xcp.regs)
/* Restore the full context -- either a simple user state save or the full,
* IRQ state save.
*/
-#define RESTORE_USERCONTEXT(tcb) z180_restoreusercontext((tcb)->xcp.regs)
+#define RESTORE_USERCONTEXT(tcb) \
+ do \
+ { \
+ if ((tcb)->xcp.cbr.cbr) \
+ { \
+ outp(Z180_MMU_CBR, (tcb)->xcp.cbr->cbr); \
+ } \
+ z180_restoreusercontext((tcb)->xcp.regs); \
+ } \
+ while (0)
/* Dump the current machine registers */
-#define _REGISTER_DUMP() z180_registerdump()
+#define _REGISTER_DUMP() \
+ z180_registerdump()
/************************************************************************************
* Public Types
@@ -123,6 +184,14 @@
*/
extern 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.
+ */
+
+extern uint8_t current_cbr;
#endif
/************************************************************************************
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.c b/nuttx/arch/z80/src/z180/z180_mmu.c
index c71f59755..076d91bef 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.c
+++ b/nuttx/arch/z80/src/z180/z180_mmu.c
@@ -120,15 +120,21 @@ static FAR struct z180_cbr_s *z180_mmu_findcbr(void)
* called very early in the boot process to get the basic operating
* memory configuration correct. This function does *not* perform all
* necessray MMU initialization... only the basics needed at power-up.
- * z180_mmu_init() must be called later to complete the entire MMU
+ * up_mmuinit() must be called later to complete the entire MMU
* initialization.
*
****************************************************************************/
void z180_mmu_lowinit(void) __naked
{
+ /* Set the CBAR register to set up the virtual address of the Bank Area and
+ * Common Area 1. Set the BBR register to set up the physical mapping for
+ * the Bank Area (the physical mapping for Common Area 1 will not be done
+ * until the first task is started.
+ */
+
__asm
- ld c, #Z180_MMU_CBR ; port
+ ld c, #Z180_MMU_CBAR ; port
ld a, #Z180_CBAR_VALUE ; value
out (c), a
@@ -139,15 +145,15 @@ void z180_mmu_lowinit(void) __naked
}
/****************************************************************************
- * Name: z180_mmu_init
+ * Name: up_mmuinit
*
* Description:
- * Perform higher level initializatin of the MMU and physical memory
+ * Perform higher level initialization of the MMU and physical memory
* memory management logic.
*
****************************************************************************/
-int z180_mmu_init(void)
+int up_mmuinit(void)
{
/* Here we use the granule allocator as a page allocator. We lie and
* say that 1 page is 1 byte.
@@ -257,7 +263,7 @@ errout_with_irq:
}
/****************************************************************************
- * Name: up_addrenv_clone
+ * Name: up_addrenv_share
*
* Description:
* This function is called from the core scheduler logic when a thread
@@ -274,8 +280,7 @@ errout_with_irq:
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
-int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
+int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb)
{
irqstate_t flags;
@@ -299,7 +304,6 @@ int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
irqrestore(flags);
return OK;
}
-#endif
/****************************************************************************
* Name: up_addrenv_instantiate
@@ -316,35 +320,55 @@ int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
* be instantiated.
*
* Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
+ * A handle that may be used with up_addrenv_restore() to restore the
+ * address environment before up_addrenv_instantiate() was called.
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
-int up_addrenv_instantiate(FAR _TCB *tcb)
+FAR void *up_addrenv_instantiate(FAR _TCB *tcb)
{
+ uint8_t oldcbr;
irqstate_t flags;
- /* Check if the task has an address environment. */
+ /* Get the current CBR value from the CBR register */
flags = irqsave();
+ cbr = inp(Z180_MMU_CBR);
+
+ /* Check if the task has an address environment. */
+
if (tcb->xcp.cbr)
{
- /* Yes... write the CBR value into CBR register */
+ /* Yes.. Write the new CBR value into CBR register */
outp(Z180_MMU_CBR, tcb->xcp.cbr.cbr);
- /* Clone the CBR by incrementing the reference counting and saving a
- * copy in the child thread's TCB.
- */
-
- ptcb->xcp.cbr.crefs++;
- ctcb->xcp.cbr = ptcb->xcp.cbr;
}
irqrestore(flags);
- return OK;
+ return (FAR void *)cbr;
+}
+
+/****************************************************************************
+ * Name: up_addrenv_restore
+ *
+ * Description:
+ * Restore an address environment using a handle previously returned by
+ * up_addrenv_instantiate().
+ *
+ * Input Parameters:
+ * handle - A handle previously returned by up_addrenv_instantiate.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int up_addrenv_restore(FAR void *handle)
+{
+ /* Restore the CBR value */
+
+ outp(Z180_MMU_CBR, (uint8_t)handle);
}
-#endif
/****************************************************************************
* Name: up_addrenv_release
@@ -364,7 +388,6 @@ int up_addrenv_instantiate(FAR _TCB *tcb)
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
int up_addrenv_release(FAR _TCB *tcb)
{
FAR struct z180_cbr_s *cbr;
@@ -401,5 +424,3 @@ int up_addrenv_release(FAR _TCB *tcb)
irqrestore(flags);
return OK;
}
-#endif
-
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.h b/nuttx/arch/z80/src/z180/z180_mmu.h
index 1a4c03406..74463427a 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.h
+++ b/nuttx/arch/z80/src/z180/z180_mmu.h
@@ -128,7 +128,7 @@
* called very early in the boot process to get the basic operating
* memory configuration correct. This function does *not* perform all
* necessray MMU initialization... only the basics needed at power-up.
- * z180_mmu_init() must be called later to complete the entire MMU
+ * up_mmuinit() must be called later to complete the entire MMU
* initialization.
*
****************************************************************************/
@@ -136,7 +136,7 @@
void z180_mmu_lowinit(void) __naked;
/****************************************************************************
- * Name: z180_mmu_init
+ * Name: up_mmuinit
*
* Description:
* Perform higher level initializatin of the MMU and physical memory
@@ -144,6 +144,6 @@ void z180_mmu_lowinit(void) __naked;
*
****************************************************************************/
-void z180_mmu_init(void);
+void up_mmuinit(void);
#endif /* __ARCH_Z80_SRC_Z180_Z180_MMU_H */
diff --git a/nuttx/arch/z80/src/z180/z180_registerdump.c b/nuttx/arch/z80/src/z180/z180_registerdump.c
index 2ccfc2f99..65ae791db 100644
--- a/nuttx/arch/z80/src/z180/z180_registerdump.c
+++ b/nuttx/arch/z80/src/z180/z180_registerdump.c
@@ -86,6 +86,8 @@ static void z180_registerdump(void)
current_regs[XCPT_IX], current_regs[XCPT_IY]);
lldbg("SP: %04x PC: %04x\n"
current_regs[XCPT_SP], current_regs[XCPT_PC]);
+ lldbg("CBAR: %02x BBR: %02x CBR: %02x\n"
+ inp(Z180_MMU_CBAR), inp(Z180_MMU_BBR), inp(Z180_MMU_CBR));
}
}
#endif