summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/z80/src')
-rw-r--r--nuttx/arch/z80/src/z180/Kconfig101
-rw-r--r--nuttx/arch/z80/src/z180/Make.defs25
-rw-r--r--nuttx/arch/z80/src/z180/z180_head.asm16
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.c405
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.h149
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.txt114
6 files changed, 784 insertions, 26 deletions
diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig
index 4eafa8da8..58abbd6f2 100644
--- a/nuttx/arch/z80/src/z180/Kconfig
+++ b/nuttx/arch/z80/src/z180/Kconfig
@@ -21,30 +21,115 @@ config Z180_TOOLCHAIN_SDCCW
endchoice
config LINKER_HOME_AREA
- hex "Start of _HOME area"
+ hex "Physical start of _HOME area"
default 0x0000
---help---
- Start of the linker HOME area. Default: 0x0000
+ Physical address of the start of the linker HOME area. Default: 0x0000
config LINKER_CODE_AREA
- hex "Start of _CODE area"
+ hex "Physical start of _CODE area"
default 0x0200
---help---
- Start of the linker _CODE area. Default: 0x0200
+ Physical address of the start of the linker _CODE area. Default: 0x0200
config LINKER_DATA_AREA
- hex "Start of _DATA area"
+ hex "Physical start of _DATA area"
default 0x8000
---help---
- Start of the linker _DATA area. Default: 0x8000
+ Physical address of the start of the linker _DATA area. Default: 0x8000
config LINKER_ROM_AT_0000
- bool "ROM at 0x0000"
+ bool "ROM at Physical 0x0000"
default n
---help---
- Some architectures may have ROM located at address zero. In this
+ Some architectures may have ROM located at physical address zero. In this
case, a special version of the "head" file must be used.
+config Z180_BANKAREA_VIRTBASE
+ hex "Virtual Start of Bank Area"
+ default 0x8000
+ ---help---
+ This setting provides the virtual address of the start of the Bank Area.
+ NOTE that 0x0000 <= Z180_BANKAREA_BASE <= Z180_COMMONAREA_BASE is required!
+ Default: 0x8000
+
+ NuttX Memory Organization:
+
+ Common Area 0: This area holds the common NuttX code that is
+ directly call-able from all application threads. Common Area
+ always starts at virtual address 0x0000 and extends to the
+ Bank Area
+
+ Base Area: This area holds the common NuttX data (including the
+ share-able heap) that is accessible from all applications and
+ extends to Common Area 1.
+
+ NOTE: That is execution from RAM, the common NuttX code and
+ data may be contiguous and lie in the same region (either
+ Common Area 0 or the Bank Area). The two regions above would
+ apply in a ROM'ed system, where Common Area 1 is ROM and the
+ Base Area is RAM.
+
+ Common Area 1: This area holds the code and data that is unique
+ to a particular task. his area extends to the end of the virtual
+ address space. All tasks share the same virtual Common Area 2
+ virtual address (but each has a unique mapping to different,
+ underlying physical addresses).
+
+config Z180_BANKAREA_PHYSBASE
+ hex "Physical Start of Bank Area"
+ default 0x08000
+ ---help---
+ This setting provides the physical address of the start of the Bank Area.
+ Default: 0x08000
+
+config Z180_COMMON1AREA_VIRTBASE
+ hex "Virtual Start of Common Area 1"
+ default 0xc000
+ ---help---
+ This setting provides the virtual address of the start of the Common
+ Area 1. NOTE that 0x0000 <= Z180_BANKAREA_BASE <= Z180_COMMONAREA_BASE
+ is required! Default: 0xc000
+
+ NuttX Memory Organization:
+
+ Common Area 0: This area holds the common NuttX code that is
+ directly call-able from all application threads. Common Area
+ always starts at virtual address 0x0000 and extends to the
+ Bank Area
+
+ Base Area: This area holds the common NuttX data (including the
+ share-able heap) that is accessible from all applications and
+ extends to Common Area 1.
+
+ NOTE: That is execution from RAM, the common NuttX code and
+ data may be contiguous and lie in the same region (either
+ Common Area 0 or the Bank Area). The two regions above would
+ apply in a ROM'ed system, where Common Area 1 is ROM and the
+ Base Area is RAM.
+
+ Common Area 1: This area holds the code and data that is unique
+ to a particular task. his area extends to the end of the virtual
+ address space. All tasks share the same virtual Common Area 2
+ virtual address (but each has a unique mapping to different,
+ underlying physical addresses).
+
+config Z180_PHYSHEAP_START
+ hex "Physical Start of Free Memory"
+ default 0x0c000
+ ---help---
+ This setting provides the physical address of the start of free physical
+ memory that will be used to allocate memory for tasks (Common Area 1).
+ Default: 0x0c000
+
+config Z180_PHYSHEAP_END
+ hex "Physical End(+1) of Free Memory"
+ default 0x100000
+ ---help---
+ This setting provides the physical address of the end(+1) of free physical
+ memory that will be used to allocate memory for tasks (Common Area 1).
+ Default: 0x100000
+
config ARCH_HAVEHEAD
bool "Board-specific Head File"
default n
diff --git a/nuttx/arch/z80/src/z180/Make.defs b/nuttx/arch/z80/src/z180/Make.defs
index d371a5d22..069f36204 100644
--- a/nuttx/arch/z80/src/z180/Make.defs
+++ b/nuttx/arch/z80/src/z180/Make.defs
@@ -35,21 +35,20 @@
ifeq ($(CONFIG_ARCH_HAVEHEAD),)
ifeq ($(CONFIG_LINKER_ROM_AT_0000),y)
-HEAD_ASRC = z180_rom.asm
+HEAD_ASRC = z180_rom.asm
else
-HEAD_ASRC = z180_head.asm
+HEAD_ASRC = z180_head.asm
endif
endif
-CMN_ASRCS =
-CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \
- up_releasestack.c up_interruptcontext.c up_blocktask.c \
- up_unblocktask.c up_exit.c up_releasepending.c \
- up_reprioritizertr.c up_idle.c up_assert.c up_doirq.c \
- up_mdelay.c up_udelay.c up_usestack.c
-
-CHIP_ASRCS = z180_saveusercontext.asm z180_restoreusercontext.asm
-CHIP_CSRCS = z180_initialstate.c z180_io.c z180_irq.c z180_copystate.c \
- z180_schedulesigaction.c z180_sigdeliver.c \
- z180_registerdump.c
+CMN_ASRCS =
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_createstack.c
+CMN_CSRCS += up_doirq.c up_exit.c up_idle.c up_initialize.c
+CMN_CSRCS += up_interruptcontext.c up_mdelay.c up_releasepending.c
+CMN_CSRCS += up_releasestack.c up_reprioritizertr.c up_unblocktask.c
+CMN_CSRCS += up_udelay.c up_usestack.c
+CHIP_ASRCS = z180_restoreusercontext.asm z180_saveusercontext.asm
+CHIP_CSRCS = z180_copystate.c z180_initialstate.c z180_io.c z180_irq.c
+CHIP_CSRCS += z180_mmu.c z180_registerdump.c z180_schedulesigaction.c
+CHIP_CSRCS += z180_sigdeliver.c
diff --git a/nuttx/arch/z80/src/z180/z180_head.asm b/nuttx/arch/z80/src/z180/z180_head.asm
index ca064160a..ddd0283e9 100644
--- a/nuttx/arch/z80/src/z180/z180_head.asm
+++ b/nuttx/arch/z80/src/z180/z180_head.asm
@@ -60,8 +60,9 @@
; Global symbols used
;**************************************************************************
- .globl _os_start ; OS entry point
- .globl _up_doirq ; Interrupt decoding logic
+ .globl _os_start ; OS entry point
+ .globl _up_doirq ; Interrupt decoding logic
+ .globl z180_mmu_lowinit ; MMU initialization logic
;**************************************************************************
; Reset entry point
@@ -70,9 +71,9 @@
.area _HEADER (ABS)
.org 0x0000
- di ; Disable interrupts
- im 1 ; Set interrupt mode 1
- jr _up_reset ; And boot the system
+ di ; Disable interrupts
+ im 1 ; Set interrupt mode 1
+ jr _up_reset ; And boot the system
;**************************************************************************
; Other reset handlers
@@ -168,6 +169,11 @@ _up_reset:
ld SP, #CONFIG_STACK_END ; Set stack pointer
+ ; Configure the MMU so that things will lie at the addresses that we
+ ; expect them to
+
+ call z180_mmu_lowinit ; Initialize the MMU
+
; Performed initialization unique to the SDCC toolchain
call gsinit ; Initialize the data section
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.c b/nuttx/arch/z80/src/z180/z180_mmu.c
new file mode 100644
index 000000000..c71f59755
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_mmu.c
@@ -0,0 +1,405 @@
+/****************************************************************************
+ * arch/z80/src/z180/z180_mmu.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* See arch/z80/src/z180/z180_mmu.txt for additional information */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/gram.h>
+
+#include "z180_mmu.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_ADDRENV
+# warning "OS address environment support is required (CONFIG_ADDRENV)"
+#endif
+
+#ifndef CONFIG_GRAN
+# warning "This file requires the granual allocator (CONFIG_GRAN)"
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifndef CONFIG_GRAN_SINGLE
+static GRAN_HANDLE g_physhandle;
+#endif
+static struct z180_cbr_s g_cbrs[CONFIG_MAX_TASKS];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_mmu_findcbr
+ *
+ * Description:
+ * Find an unused struture in g_cbrs (i.e., one with reference count == 0).
+ * If a structure is found, its reference count is set to one and a pointer
+ * to the structure is returned.
+ *
+ ****************************************************************************/
+
+static FAR struct z180_cbr_s *z180_mmu_findcbr(void)
+{
+ int i;
+
+ for (i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ FAR struct z180_cbr_s *cbr = &g_cbrs[i];
+ if (cbr->crefs == 0)
+ {
+ cbr->crefs = 1;
+ return cbr;
+ }
+ }
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: z180_mmu_freecbr
+ *
+ * Description:
+ * Free a struture in g_cbrs by setting its reference count to 0;
+ *
+ ****************************************************************************/
+
+#define z180_mmu_freecbr(cbr) (cbr)->crefs = 0
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_mmu_lowinit
+ *
+ * Description:
+ * Low-level, power-up initialization of the z180 MMU. this must be
+ * 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
+ * initialization.
+ *
+ ****************************************************************************/
+
+void z180_mmu_lowinit(void) __naked
+{
+ __asm
+ ld c, #Z180_MMU_CBR ; port
+ ld a, #Z180_CBAR_VALUE ; value
+ out (c), a
+
+ ld c, #Z180_MMU_BBR ; port
+ ld a, #Z180_BBR_VALUE ; value
+ out (c), a
+ __endasm;
+}
+
+/****************************************************************************
+ * Name: z180_mmu_init
+ *
+ * Description:
+ * Perform higher level initializatin of the MMU and physical memory
+ * memory management logic.
+ *
+ ****************************************************************************/
+
+int z180_mmu_init(void)
+{
+ /* Here we use the granule allocator as a page allocator. We lie and
+ * say that 1 page is 1 byte.
+ */
+
+#ifdef CONFIG_GRAN_SINGLE
+return gran_initialize((FAR void *)Z180_PHYSHEAP_STARTPAGE,
+ Z180_PHYSHEAP_NPAGES, 0, 0);
+#else
+g_physhandle = gran_initialize((FAR void *)Z180_PHYSHEAP_STARTPAGE,
+ Z180_PHYSHEAP_NPAGES, 0, 0);
+return g_physhandle ? OK : -ENOMEM;
+#endif
+}
+
+/****************************************************************************
+ * Name: up_addrenv_create
+ *
+ * Description:
+ * This function is called from the binary loader logic when a new
+ * task is created in RAM in order to instantiate an address environment for
+ * the task.
+ *
+ * Input Parameters:
+ * tcb - The TCB of the task needing the address environment.
+ * envsize - The size (in bytes) of the address environment needed by the
+ * task.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int up_addrenv_create(FAR _TCB *tcb, size_t envsize)
+{
+ FAR struct z180_cbr_s *cbr;
+ irqstate_t flags;
+ uintptr_t alloc;
+ unsigned int npages;
+ int ret;
+
+ /* Make sure that there is no address environment in place on this TCB */
+
+ DEBUGASSERT(tcb->xcp.cbr == NULL);
+
+ /* Convert the size from bytes to numbers of pages */
+
+ npages = PHYS_ALIGNUP(envsize);
+ if (npages < 1)
+ {
+ /* No address environment... but I suppose that is not an error */
+
+ sdbg("ERROR: npages is zero\n");
+ return OK;
+ }
+
+ /* Allocate a structure in the common .bss to hold information about the
+ * task's address environment. NOTE that this is not a part of the TCB,
+ * but rather a break-away structure that can be shared by the task as
+ * well as other threads. That is necessary because the life of the
+ * address of environment might be longer than the life of the task.
+ */
+
+ flags = irqsave();
+ cbr = z180_mmu_findcbr();
+ if (!cbr)
+ {
+ sdbg("ERROR: No free CBR structures\n");
+ ret = -ENOMEM;
+ goto errout_with_irq
+ }
+
+ /* Now allocate the physical memory to back up the address environment */
+
+
+#ifdef CONFIG_GRAN_SINGLE
+ alloc = (uintptr_t)gran_alloc(npages);
+#else
+ alloc = (uintptr_t)gran_alloc(g_physhandle, npages);
+#endif
+ if (!alloc)
+ {
+ sdbg("ERROR: Failed to allocate %d pages\n", npages);
+ ret = -ENOMEM;
+ goto errout_with_cbr;
+ }
+
+ /* Save the information in the CBR structure. Note that alloc is in
+ * 4KB pages, already in the right form for the CBR.
+ */
+
+ DEBUGASSERT(alloc <= 0xff);
+
+ cbr->cbr = alloc;
+ cbr->pages = npages;
+ tcb->xcp.cbr = cbr;
+
+ irqrestore(flags);
+ return OK;
+
+errout_with_cbr:
+ z180_mmu_freecbr(cbr);
+
+errout_with_irq:
+ irqrestore(flags);
+ return ret;
+}
+
+/****************************************************************************
+ * Name: up_addrenv_clone
+ *
+ * Description:
+ * This function is called from the core scheduler logic when a thread
+ * is created that needs to share the address ennvironment of its parent
+ * task. In this case, the parent's address environment needs to be
+ * "cloned" for the child.
+ *
+ * Input Parameters:
+ * ptcb - The TCB of the parent task that has the address environment.
+ * ctcb - The TCB of the child thread needing the address environment.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
+{
+ irqstate_t flags;
+
+ /* Make sure that the child has no address environment. It is okay if
+ * if the parent does not have one.
+ */
+
+ DEBUGASSERT(ctcb->xcp.cbr == NULL);
+
+ flags = irqsave();
+ if (ptcb->xcp.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;
+}
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_instantiate
+ *
+ * Description:
+ * After an address environment has been established for a task (via
+ * up_addrenv_create(). This function may be called to to instantiate
+ * that address environment in the virtual address space. this might be
+ * necessary, for example, to load the code for the task from a file or
+ * to access address environment private data.
+ *
+ * Input Parameters:
+ * tcb - The TCB of the task or thread whose the address environment will
+ * be instantiated.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_instantiate(FAR _TCB *tcb)
+{
+ irqstate_t flags;
+
+ /* Check if the task has an address environment. */
+
+ flags = irqsave();
+ if (tcb->xcp.cbr)
+ {
+ /* Yes... write the 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;
+}
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_release
+ *
+ * Description:
+ * This function is called when a task or thread exits in order to release
+ * its reference to an address environment. When there are no further
+ * references to an address environment, that address environment should
+ * be destroyed.
+ *
+ * Input Parameters:
+ * tcb - The TCB of the task or thread whose the address environment will
+ * be released.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_release(FAR _TCB *tcb)
+{
+ FAR struct z180_cbr_s *cbr;
+ irqstate_t flags;
+
+ /* Check if the task has an address environment. */
+
+ flags = irqsave();
+ cbr = tcb->xcp.cbr;
+ if (cbr)
+ {
+ /* Nullify the reference to the CBR structgure and decrement the number
+ * of references on the CBR.
+ */
+
+ tcb->xcp.cbr = NULL;
+
+ /* If the reference count would decrement to zero, then free the CBR
+ * structure.
+ */
+
+ if (cbr->crefs <= 1)
+ {
+ z180_mmu_freecbr(cbr);
+ }
+ else
+ {
+ /* Otherwise, just decrement the reference count */
+
+ cbr->crefs--;
+ }
+ }
+
+ 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
new file mode 100644
index 000000000..1a4c03406
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_mmu.h
@@ -0,0 +1,149 @@
+/****************************************************************************
+ * arch/z80/src/z180/z180_mmu.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_Z80_SRC_Z180_Z180_MMU_H
+#define __ARCH_Z80_SRC_Z180_Z180_MMU_H
+
+/* See arch/z80/src/z180/z180_mmu.txt for additional information */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "z180_iomap.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/* Virtual addresses */
+
+#ifndef CONFIG_Z180_BANKAREA_VIRTBASE
+# warning "Assuming Bank Area at virtual address 0x8000"
+# define CONFIG_Z180_BANKAREA_VIRTBASE 0x8000
+#endif
+
+#ifndef CONFIG_Z180_COMMON1AREA_VIRTBASE
+# warning "Assuming Common Area 1 at virtual address 0xc000"
+# define CONFIG_Z180_COMMON1AREA_VIRTBASE 0xc000
+#endif
+
+#if CONFIG_Z180_BANKAREA_VIRTBASE > CONFIG_Z180_COMMON1AREA_VIRTBASE
+# error "CONFIG_Z180_BANKAREA_VIRTBASE > CONFIG_Z180_COMMON1AREA_VIRTBASE"
+#endif
+
+/* Physical addresses */
+
+#ifndef CONFIG_Z180_BANKAREA_PHYSBASE
+# warning "Assuming Bank Area 1 at physical address 0x080000"
+# define CONFIG_Z180_BANKAREA_PHYSBASE 0x08000
+#endif
+
+#ifndef CONFIG_Z180_PHYSHEAP_START
+# warning "Assuming physical heap starts at physical address 0x0c000"
+# define CONFIG_Z180_PHYSHEAP_START 0x0c000
+#endif
+
+#ifndef CONFIG_Z180_PHYSHEAP_END
+# warning "Assuming physical heap ends at physical address 0x100000"
+# define CONFIG_Z180_PHYSHEAP_END 0x100000
+#endif
+
+#if CONFIG_Z180_BANKAREA_PHYSBASE > CONFIG_Z180_PHYSHEAP_START
+# error "CONFIG_Z180_BANKAREA_PHYSBASE > CONFIG_Z180_PHYSHEAP_START"
+#endif
+
+#if CONFIG_Z180_PHYSHEAP_START > CONFIG_Z180_PHYSHEAP_END
+# error "CONFIG_Z180_PHYSHEAP_START > CONFIG_Z180_PHYSHEAP_END"
+#endif
+
+/* Each page is 4KB */
+
+#define Z180_PAGESHIFT (12)
+#define Z180_PAGESIZE (1 << Z180_PAGESHIFT)
+#define Z180_PAGEMASK (Z180_PAGESIZE - 1)
+#define PHYS_ALIGN(phys) ((phys) >> Z180_PAGESHIFT)
+#define PHYS_ALIGNUP(phys) (((phys) + Z180_PAGEMASK) >> Z180_PAGESHIFT)
+
+/* Physical pages */
+
+#define Z180_BANKAREA_PHYSPAGE PHYS_ALIGN(CONFIG_Z180_BANKAREA_PHYSBASE)
+#define Z180_PHYSHEAP_STARTPAGE PHYS_ALIGN(CONFIG_Z180_PHYSHEAP_START)
+#define Z180_PHYSHEAP_ENDPAGE PHYS_ALIGN(CONFIG_Z180_PHYSHEAP_END)
+#define Z180_PHYSHEAP_NPAGES (Z180_PHYSHEAP_ENDPAGE - Z180_PHYSHEAP_STARTPAGE + 1)
+
+/* 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)
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: z180_mmu_lowinit
+ *
+ * Description:
+ * Low-level, power-up initialization of the z180 MMU. this must be
+ * 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
+ * initialization.
+ *
+ ****************************************************************************/
+
+void z180_mmu_lowinit(void) __naked;
+
+/****************************************************************************
+ * Name: z180_mmu_init
+ *
+ * Description:
+ * Perform higher level initializatin of the MMU and physical memory
+ * memory management logic.
+ *
+ ****************************************************************************/
+
+void z180_mmu_init(void);
+
+#endif /* __ARCH_Z80_SRC_Z180_Z180_MMU_H */
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.txt b/nuttx/arch/z80/src/z180/z180_mmu.txt
new file mode 100644
index 000000000..e12f41e9b
--- /dev/null
+++ b/nuttx/arch/z80/src/z180/z180_mmu.txt
@@ -0,0 +1,114 @@
+The MMU translates every memory address from 16 to 20 bits. The MMU uses
+three internal control registers. On reset the MMU gives a straight logical
+to physical mapping, simulating the Z80 and, of course, limiting the address
+space to 64k.
+
+Logical Address Spaces
+======================
+
+The 64KB CPU logical address space is interpreted by the MMU as consisting
+of up to three separate logical address areas:
+
+ Common Area 0,
+ Bank Area, and
+ Common Area 1.
+
+Common 0, if it exists, always starts at logical address 0000 and runs up
+to the Bank Area. The Bank Area then runs to the start of Common Area 1.
+
+Registers
+=========
+
+CBAR (Comman/Bank Area Register)
+
+ CBAR is an 8 bit I/O port that can be accessed by the processor's OUT and
+ IN instructions. The lower 4-bits of CBAR (BA) specify the starting logical
+ address of the Bank Area, and the upper 4-bits (CA) give the start of
+ Common Area 1. These bits determine the upper four bits of the 16-bit
+ address. If CBAR were 0xa8, then the Base Area starts at logical address
+ 0x8000 and Common Area 1 starts at logical address 0xa000. This gives a
+ mapping granualarity of 4Kb in the logical address space.
+
+ The CA and BA fields of CBAR may be freely programmed subject only to the
+ restriction that CA may never be less than BA.
+
+BBAR (Base Area Bank Register)
+
+ BBR specifies the starting physical address of the base area (the logical
+ start address is in CBAR).
+
+CBR (Common Bank Register)
+
+ CBR provides the same information for Common Area 1.
+
+Both the BBAR and the CBR specify the upper 8-bits of the 20-bit physical
+address in the mapping. Hence, mapping is performed with a granularity of
+4Kb in the physical address space.
+
+Physical to Logical Address Mapping
+===================================
+
+A simple formula gives the translation from logical to physical address for
+the Bank Area:
+
+ Physical = Logical + (BBR * 4096)
+
+The same formula gives Common Area 1:
+
+ Physical = Logical + (CBR * 4096)
+
+Reset Configuration
+===================
+
+On reset, the CBAR is set to 0xf0, and CBR and BBR are set to 0x00. This
+maps logical to physical with no translation; the Bank Area starts at
+logical address 0x0000 and Common 1 at 0xf000. The Bank Area starts at
+phsycial address 0x00000 (BBR=0), as does Common Area 1 (CBR=0). If the
+logical address is 0x1000, then the MMU allocates this to the Bank Area
+and adds the physical base of bank to it (0x00000), giving a translated
+address of 0x01000. Similarly, logical 0xf800 is in Common Area 1, and
+translates to 0x0f800.
+
+Configurations
+==============
+
+You can divide the logical address space into one, two, or three areas.
+
+1) Three areas:
+
+ CBAR:CA > CBAR:BA > 0x0000
+
+2a) Two areas (Bank Area and Common Area 1):
+
+ CBAR:CA > CBAR:BA = 0x0000
+
+2a) Two areas (Common Area 0 and Common Area 1):
+
+ CBAR:CA = CBAR:BA > 0x0000
+
+3) One area (Common Area 1):
+
+ CBAR:CA = CBAR:BA = 0x0000
+
+NuttX Memory Organization
+=========================
+
+Common Area 0: This area holds the common NuttX code that is directly
+call-able from all application threads. Common Area always starts at
+logical address 0x0000 and extends to the Bank Area
+
+Base Area: This area holds the common NuttX data (including the share-
+able heap) that is accessible from all applications and extends to
+Common Area 1.
+
+NOTE: That is execution from RAM, the common NuttX code and data may
+be contiguous and lie in the same areas (either Common Area 0 or the
+Bank Area). The two areas above would apply in a ROM'ed system, where
+Common Area 1 is ROM and the Base Area is RAM.
+
+Common Area 1: This area holds the code and data that is unique to
+a particular task. This area extends to the end of the logical address
+space. All tasks share the same logical Common Area 2 logical address
+(in the CBAR), but each has a unique mapping to different, underlying
+physical addresses. Each task will then have its own, unique CBR value
+that must be restored with each context switch to the task.