z20X: Continued development of the W25 Bootloader.

Kconfig files.  Repartition some functionality.  Bootloader support will need to be provided in logic under arch/z80/src/ez80 so the critical configuration selections were moved the Kconfig file there.

arch/z80/src/ez80/ez80_i2c.h:  Rename arch/z80/src/ez80/ez80f91_i2c.h.  It is sharable by both ez80f91 and ez80f92.

arch/z80/src/ez80/:  Add logic to perform an additional level of interrupt redirection.  This is necessary because the the interrupt handling is part of the loader FLASH-based logic.  In order to share interrupts with the program loaded into RAM by the loader, another layer or redirection is required to get control to the interrupt handlers in the loaded program.  See ez809f2_loader.asm and ez80f92_program.asm

boards/z80/ez80/z20x/scripts:  Reduce size of the interrupt re-direction buffer from 1Kb to 512b.
This commit is contained in:
Gregory Nutt 2020-03-03 11:02:43 -06:00 committed by Alan Carvalho de Assis
parent a21120e3b6
commit 2eff5a6c63
27 changed files with 890 additions and 307 deletions

View File

@ -72,6 +72,23 @@ config EZ80_ZDSII_V533
endchoice # ZDS-II Toolchain version
config EZ80_BOOTLOADER
bool
default n
select BOOT_RUNFROMFLASH
---help---
Binary image is a bootloader that may require special properties
such as re-direction of interrupts (eZ80F92)
config EZ80_PROGRAM
bool
default n
select CONFIG_BOOT_RUNFROMEXTSRAM
---help---
Binary image is a RAM-resident program loaded by a bootloader and
may require special properties such as re-direction of interrupts
(eZ80F92)
menu "ez80 Peripheral Support"
config EZ80_UART0

View File

@ -1,39 +1,24 @@
############################################################################
# arch/z80/src/ez80/Make.defs
#
# Copyright (C) 2008-2009, 2014 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# Licensed to the Apache Software Foundation (ASF) under one or more
# contributor license agreements. See the NOTICE file distributed with
# this work for additional information regarding copyright ownership. The
# ASF licenses this file to you under the Apache License, Version 2.0 (the
# "License"); you may not use this file except in compliance with the
# License. You may obtain a copy of the License at
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
# http://www.apache.org/licenses/LICENSE-2.0
#
# 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.
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
# License for the specific language governing permissions and limitations
# under the License.
#
############################################################################
HEAD_ASRC = ez80_vectors.asm
HEAD_ASRC =
HEAD_SSRC =
CMN_SSRCS =
@ -49,14 +34,26 @@ CMN_CSRCS += up_stackdump.c
endif
CHIP_ASRCS = ez80_startup.asm ez80_io.asm ez80_irqsave.asm
CHIP_ASRCS += ez80_irqcommon.asm
CHIP_ASRCS += ez80_saveusercontext.asm ez80_restorecontext.asm
ifeq ($(CONFIG_ARCH_CHIP_EZ80F91),y)
HEAD_ASRC = ez80_reset.asm
CHIP_ASRCS += ez80f91_init.asm ez80f91_handlers.asm
endif
ifeq ($(CONFIG_ARCH_CHIP_EZ80F92),y)
CHIP_ASRCS += ez80f92_init.asm ez80f92_handlers.asm
CHIP_ASRCS += ez80f92_init.asm
ifeq ($(CONFIG_EZ80_BOOTLOADER),y)
HEAD_ASRC = ez80_reset.asm
CHIP_ASRCS += ez80f92_loader.asm
else ifeq ($(CONFIG_EZ80_PROGRAM),y)
HEAD_ASRC = ez80_progentry.asm
CHIP_ASRCS += ez80f92_program.asm
else
HEAD_ASRC = ez80_reset.asm
CHIP_ASRCS += ez80f92_handlers.asm
endif
endif
ifeq ($(CONFIG_ARCH_STACKDUMP),y)

View File

@ -1,36 +1,20 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_i2c.c
*
* Copyright(C) 2009, 2011, 2013, 2016-2017 Gregory Nutt. All rights
* reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* http://www.apache.org/licenses/LICENSE-2.0
*
* 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.
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
@ -54,7 +38,7 @@
#include <arch/board/board.h>
#include "ez80f91.h"
#include "ez80f91_i2c.h"
#include "ez80_i2c.h"
/****************************************************************************
* Pre-processor Definitions
@ -124,6 +108,7 @@ const struct i2c_ops_s g_ops =
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: ez80_i2c_semtake/ez80_i2c_semgive
*
@ -200,7 +185,7 @@ static uint16_t ez80_i2c_getccr(uint32_t fscl)
* The minimum value of the fsamp is given by:
*/
fsamp = 10 * fscl;
fsamp = 10 * fscl;
/* Now, serarch for the smallest value of N that results in the actual
* fsamp >= the ideal fsamp. Fortunately, we only have to check at most
@ -261,12 +246,12 @@ static uint16_t ez80_i2c_getccr(uint32_t fscl)
m = ftmp / fscl;
if (m > 0)
{
if (--m > 15)
{
m = 15;
}
}
{
if (--m > 15)
{
m = 15;
}
}
/* Return the value for CCR */
@ -438,8 +423,8 @@ static int ez80_i2c_sendaddr(struct ez80_i2cdev_s *priv, uint8_t readbit)
sr = ez80_i2c_waitiflg();
if (sr != I2C_SR_MADDRWRACK && sr != I2C_SR_MADDRWR)
{
i2cerr("ERROR: Bad ADDR10H status: %02x\n", sr);
goto failure;
i2cerr("ERROR: Bad ADDR10H status: %02x\n", sr);
goto failure;
}
/* Now send the lower 8 bits of the 10-bit address */
@ -859,7 +844,7 @@ static int ez80_i2c_transfer(FAR struct i2c_master_s *dev,
nostop = false;
if (i < (count - 1))
{
{
FAR struct i2c_msg_s *next;
/* No... Check if the next message should have a repeated start or

View File

@ -1,41 +1,25 @@
/************************************************************************************
* arch/z80/src/ez80/ez80f91_i2c.h
* arch/z80/src/chip/ez80f91_i2c.h
* arch/z80/src/ez80/ez80_i2c.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* http://www.apache.org/licenses/LICENSE-2.0
*
* 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.
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
************************************************************************************/
#ifndef __ARCH_Z80_SRC_EZ80_EZ80F91_I2C_H
#define __ARCH_Z80_SRC_EZ80_EZ80F91_I2C_H
#ifndef __ARCH_Z80_SRC_EZ80_EZ80_I2C_H
#define __ARCH_Z80_SRC_EZ80_EZ80_I2C_H
/************************************************************************************
* Included Files
@ -47,30 +31,37 @@
* Pre-processor Definitions
************************************************************************************/
/* I2C Registers ******************************************************************/
/* I2C Registers *******************************************************************/
/* Provided in ez80f91.h */
/* I2C Register Bit Definitions ***************************************************/
/* I2C Register Bit Definitions ****************************************************/
/* Slave Address Register (SAR) Bit Definitions */
#define I2C_SAR_GCE (1 << 0) /* Bit 0: 1=I2C enabled to recognize the General Call Address */
#define I2C_SAR_SLA_SHIFT 1 /* Bits 1-7: 7-bit address or upper 2 bits in 10-bit mode */
#define I2C_SAR_GCE (1 << 0) /* Bit 0: 1=I2C enabled to recognize the
* General Call Address */
#define I2C_SAR_SLA_SHIFT 1 /* Bits 1-7: 7-bit address or upper 2 bits in
* 10-bit mode */
#define I2C_SAR_SLA_MASK (0x7f << 1)
/* Extended Slave Address Register (XSAR) Bit Definitions */
/* Bits 0-7: Least significant 8-bits of 10-bit slave address */
/* Data Byte Register (DR) Bit Definitions */
/* Bits 0-7: I2C byte data */
/* Control (CTL) Register Bit Definitions */
/* Bits 0-1: Reserved */
#define I2C_CTL_AAK (1 << 2) /* Bit 2: 1=Acknowledge */
#define I2C_CTL_IFLG (1 << 3) /* Bit 3: 1=I2C interrupt flag is set */
#define I2C_CTL_STP (1 << 4) /* Bit 4: 1=Master mode stop-transmit STOP condition on the bus */
#define I2C_CTL_STA (1 << 5) /* Bit 5: 1=Master mode start-transmit START condition on the bus */
#define I2C_CTL_STP (1 << 4) /* Bit 4: 1=Master mode stop-transmit STOP
* condition on the bus */
#define I2C_CTL_STA (1 << 5) /* Bit 5: 1=Master mode start-transmit
* START condition on the bus */
#define I2C_CTL_ENAB (1 << 6) /* Bit 6: 1=I2C bus (SCL/SDA) is enabled */
#define I2C_CTL_IEN (1 << 7) /* Bit 7: 1=I2C interrupt is enabled */
@ -79,35 +70,61 @@
#define I2C_SR_SHIFT 3 /* Bits 3-7: 5-bit status code */
#define I2C_SR_MASK (0x1c << I2C_SR_SHIFT)
#define I2C_SR_BUSERR 0x00 /* Bus error */
#define I2C_SR_MSTART 0x08 /* START condition transmitted */
#define I2C_SR_MREPSTART 0x10 /* Repeated START condition transmitted */
#define I2C_SR_MADDRWRACK 0x18 /* Address and Write bit transmitted, ACK received */
#define I2C_SR_MADDRWR 0x20 /* Address and Write bit transmitted, ACK not received */
#define I2C_SR_MDATAWRACK 0x28 /* Data byte transmitted in MASTER mode, ACK received */
#define I2C_SR_MDATAWR 0x30 /* Data byte transmitted in MASTER mode, ACK not received */
#define I2C_SR_MADDRWRACK 0x18 /* Address and Write bit transmitted, ACK
* received */
#define I2C_SR_MADDRWR 0x20 /* Address and Write bit transmitted, ACK
* not received */
#define I2C_SR_MDATAWRACK 0x28 /* Data byte transmitted in MASTER mode,
* ACK received */
#define I2C_SR_MDATAWR 0x30 /* Data byte transmitted in MASTER mode,
* ACK not received */
#define I2C_SR_ARBLOST1 0x38 /* Arbitration lost in address or data byte */
#define I2C_SR_MADDRRDACK 0x40 /* Address and Read bit transmitted, ACK received */
#define I2C_SR_MADDRRD 0x48 /* Address and Read bit transmitted, ACK not received */
#define I2C_SR_MDATARDACK 0x50 /* Data byte received in MASTER mode, ACK transmitted */
#define I2C_SR_MDATARDNAK 0x58 /* Data byte received in MASTER mode, NACK transmitted */
#define I2C_SR_SADDRWRACK 0x60 /* Slave address and Write bit received, ACK transmitted */
#define I2C_SR_ARBLOST2 0x68 /* Arbitration lost in address as master, slave address and Write bit received, ACK transmitted */
#define I2C_SR_SGCARDACK 0x70 /* General Call address received, ACK transmitted */
#define I2C_SR_ARBLOST3 0x78 /* Arbitration lost in address as master, General Call address received, ACK transmitted */
#define I2C_SR_SDATARDACK 0x80 /* Data byte received after slave address received, ACK transmitted */
#define I2C_SR_SDATARDNAK 0x88 /* Data byte received after slave address received, NACK transmitted */
#define I2C_SR_SDATAGCAACK 0x90 /* Data byte received after General Call received, ACK transmitted */
#define I2C_SR_SDATAGCANAK 0x98 /* Data byte received after General Call received, NACK transmitted */
#define I2C_SR_SSTOP 0xa0 /* STOP or repeated START condition received in SLAVE mode */
#define I2C_SR_SSADDRRDACK 0xa8 /* Slave address and Read bit received, ACK transmitted */
#define I2C_SR_ARBLOST4 0xb0 /* Arbitration lost in address as master, slave address and Read bit received, ACK transmitted */
#define I2C_SR_SDATAWRACK 0xb8 /* Data byte transmitted in SLAVE mode, ACK received */
#define I2C_SR_SDATAWR 0xc0 /* Data byte transmitted in SLAVE mode, ACK not received */
#define I2C_SR_SLDATAWR 0xc8 /* Last byte transmitted in SLAVE mode, ACK received */
#define I2C_SR_MADDR2WRACK 0xd0 /* Second Address byte and Write bit transmitted, ACK received */
#define I2C_SR_MADDR2WR 0xd8 /* Second Address byte and Write bit transmitted, ACK not received */
#define I2C_SR_MADDRRDACK 0x40 /* Address and Read bit transmitted, ACK
* received */
#define I2C_SR_MADDRRD 0x48 /* Address and Read bit transmitted, ACK no
* received */
#define I2C_SR_MDATARDACK 0x50 /* Data byte received in MASTER mode, ACK
* transmitted */
#define I2C_SR_MDATARDNAK 0x58 /* Data byte received in MASTER mode, NACK
* transmitted */
#define I2C_SR_SADDRWRACK 0x60 /* Slave address and Write bit received, ACK
* transmitted */
#define I2C_SR_ARBLOST2 0x68 /* Arbitration lost in address as master,
* slave address and Write bit received, ACK
* transmitted */
#define I2C_SR_SGCARDACK 0x70 /* General Call address received, ACK
* transmitted */
#define I2C_SR_ARBLOST3 0x78 /* Arbitration lost in address as master,
* General Call address received, ACK
* transmitted */
#define I2C_SR_SDATARDACK 0x80 /* Data byte received after slave address
* received, ACK transmitted */
#define I2C_SR_SDATARDNAK 0x88 /* Data byte received after slave address
* received, NACK transmitted */
#define I2C_SR_SDATAGCAACK 0x90 /* Data byte received after General Call
* received, ACK transmitted */
#define I2C_SR_SDATAGCANAK 0x98 /* Data byte received after General Call
* received, NACK transmitted */
#define I2C_SR_SSTOP 0xa0 /* STOP or repeated START condition received
* in SLAVE mode */
#define I2C_SR_SSADDRRDACK 0xa8 /* Slave address and Read bit received, ACK
* transmitted */
#define I2C_SR_ARBLOST4 0xb0 /* Arbitration lost in address as master,
* slave address and Read bit received, ACK
* transmitted */
#define I2C_SR_SDATAWRACK 0xb8 /* Data byte transmitted in SLAVE mode, ACK
* received */
#define I2C_SR_SDATAWR 0xc0 /* Data byte transmitted in SLAVE mode, ACK
* not received */
#define I2C_SR_SLDATAWR 0xc8 /* Last byte transmitted in SLAVE mode, ACK
* received */
#define I2C_SR_MADDR2WRACK 0xd0 /* Second Address byte and Write bit
* transmitted, ACK received */
#define I2C_SR_MADDR2WR 0xd8 /* Second Address byte and Write bit
* transmitted, ACK not received */
#define I2C_SR_NONE 0xf8 /* No relevant status information, IFLG = 0 */
/* Clock Control Register (CCR) Bit Definitions */
@ -118,6 +135,7 @@
#define I2C_CCR_MMASK (0x0f << I2C_CCR_MSHIFT)
/* Software Reset Register (SRR) Bit Definitions */
/* Writing any value to this register performs a software reset of the I2C module */
/************************************************************************************
@ -183,4 +201,4 @@ int ez80_i2cbus_uninitialize(FAR struct i2c_master_s *dev);
#endif /* __cplusplus */
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_Z80_SRC_EZ80_EZ80F91_I2C_H */
#endif /* __ARCH_Z80_SRC_EZ80_EZ80_I2C_H */

View File

@ -1,35 +1,20 @@
;**************************************************************************
; arch/z80/src/ez80/ez80_vectors.asm
; arch/z80/src/ez80/ez80_irqcommon.asm
;
; Copyright (C) 2008-2009, 2020 Gregory Nutt. All rights reserved.
; Author: Gregory Nutt <gnutt@nuttx.org>
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; Redistribution and use in source and binary forms, with or without
; modification, are permitted provided that the following conditions
; are met:
; http://www.apache.org/licenses/LICENSE-2.0
;
; 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.
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
;**************************************************************************
@ -37,85 +22,36 @@
; Constants
;**************************************************************************
; Bits in the Z80 FLAGS register *****************************************
; Bits in the Z80 FLAGS register ******************************************
EZ80_C_FLAG EQU 01h ; Bit 0: Carry flag
EZ80_N_FLAG EQU 02h ; Bit 1: Add/Subtract flag
EZ80_C_FLAG EQU 01h ; Bit 0: Carry flag
EZ80_N_FLAG EQU 02h ; Bit 1: Add/Subtract flag
EZ80_PV_FLAG EQU 04h ; Bit 2: Parity/Overflow flag
EZ80_H_FLAG EQU 10h ; Bit 4: Half carry flag
EZ80_Z_FLAG EQU 40h ; Bit 5: Zero flag
EZ80_S_FLAG EQU 80h ; Bit 7: Sign flag
EZ80_H_FLAG EQU 10h ; Bit 4: Half carry flag
EZ80_Z_FLAG EQU 40h ; Bit 5: Zero flag
EZ80_S_FLAG EQU 80h ; Bit 7: Sign flag
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref _ez80_startup
xref _z80_doirq
;**************************************************************************
; Global Symbols Exported
;**************************************************************************
xdef _ez80_reset
xdef _ez80_rstcommon
xdef _ez80_irq_common
;**************************************************************************
; Macros
;**************************************************************************
; Define one reset handler
; 1. Disable interrupts
; 2. Clear mixed memory mode (MADL) flag
; 3. jump to initialization procedure with jp.lil to set ADL
rstvector: macro
di
rsmix
jp.lil _ez80_startup
endmac rstvector
;**************************************************************************
; Reset entry points
;**************************************************************************
define .RESET, space = ROM
segment .RESET
_ez80_reset:
_rst0:
rstvector
_rst8:
rstvector
_rst10:
rstvector
_rst18:
rstvector
_rst20:
rstvector
_rst28:
rstvector
_rst30:
rstvector
_rst38:
rstvector
ds %26
_nmi:
retn
;**************************************************************************
; Startup logic
; Common Interrupt handler
;**************************************************************************
define .STARTUP, space = ROM
segment .STARTUP
.assume ADL=1
;**************************************************************************
; Common Interrupt handler
;**************************************************************************
_ez80_rstcommon:
_ez80_irq_common:
; Create a register frame. SP points to top of frame + 4, pushes
; decrement the stack pointer. Already have

View File

@ -0,0 +1,44 @@
;**************************************************************************
; arch/z80/src/ez80/ez80_progentry.asm
;
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; http://www.apache.org/licenses/LICENSE-2.0
;
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
;**************************************************************************
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref _ez80_startup
;**************************************************************************
; Global Symbols Exported
;**************************************************************************
xdef _ez80_reset
;**************************************************************************
; Reset entry points
;**************************************************************************
define .RESET, space = RAM
segment .RESET
_ez80_reset:
di ; Disable interrupts
rsmix ; Set MADL control bit to 0
jp.lil _ez80_startup ; Perform normal startup
end

View File

@ -0,0 +1,75 @@
;**************************************************************************
; arch/z80/src/ez80/ez80_reset.asm
;
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; http://www.apache.org/licenses/LICENSE-2.0
;
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
;**************************************************************************
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref _ez80_startup
;**************************************************************************
; Global Symbols Exported
;**************************************************************************
xdef _ez80_reset
;**************************************************************************
; Macros
;**************************************************************************
; Define one reset handler
; 1. Disable interrupts
; 2. Clear mixed memory mode (MADL) flag
; 3. jump to initialization procedure with jp.lil to set ADL
rstvector: macro
di
rsmix
jp.lil _ez80_startup
endmac rstvector
;**************************************************************************
; Reset entry points
;**************************************************************************
define .RESET, space = ROM
segment .RESET
_ez80_reset:
_rst0:
rstvector
_rst8:
rstvector
_rst10:
rstvector
_rst18:
rstvector
_rst20:
rstvector
_rst28:
rstvector
_rst30:
rstvector
_rst38:
rstvector
ds %26
_nmi:
retn
end

View File

@ -1,40 +1,21 @@
;**************************************************************************
; arch/z80/src/ez80/ez80_startup.asm
;
; Copyright (C) 2008 Gregory Nutt. All rights reserved.
; Author: Gregory Nutt <gnutt@nuttx.org>
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; Redistribution and use in source and binary forms, with or without
; modification, are permitted provided that the following conditions
; are met:
; http://www.apache.org/licenses/LICENSE-2.0
;
; 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.
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
; 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
;**************************************************************************
;**************************************************************************
@ -48,7 +29,7 @@ EZ80_FLASH_ADDR_U EQU %f7
EZ80_FLASH_CTRL EQU %f8
;**************************************************************************
; Global symbols used
; Imported Symbols
;**************************************************************************
xref _ez80_init

View File

@ -18,19 +18,11 @@
;
;**************************************************************************
;**************************************************************************
; Constants
;**************************************************************************
; The IRQ number to use for unused vectors
EZ80_UNUSED EQU 40h
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref _ez80_rstcommon
xref _ez80_irq_common
;**************************************************************************
; Global Symbols Exported
@ -42,7 +34,8 @@ EZ80_UNUSED EQU 40h
; Constants
;**************************************************************************
NVECTORS EQU 64 ; max possible interrupt vectors
NVECTORS EQU 64 ; Max possible interrupt vectors
EZ80_UNUSED EQU 64 ; Denotes an unused vector
;**************************************************************************
; Macros
@ -56,7 +49,7 @@ irqhandler: macro vectno
; Offset 8: Return PC is already on the stack
push af ; Offset 7: AF (retaining flags)
ld a, #vectno ; A = vector number
jp _ez80_rstcommon ; Remaining RST handling is common
jp _ez80_irq_common ; Remaining RST handling is common
endmac irqhandler
;**************************************************************************

View File

@ -30,7 +30,7 @@ EZ80_UNUSED EQU 40h
; Global Symbols Imported
;**************************************************************************
xref _ez80_rstcommon
xref _ez80_irq_common
;**************************************************************************
; Global Symbols Exported
@ -56,7 +56,7 @@ irqhandler: macro vectno
; Offset 8: Return PC is already on the stack
push af ; Offset 7: AF (retaining flags)
ld a, #vectno ; A = vector number
jp _ez80_rstcommon ; Remaining RST handling is common
jp _ez80_irq_common ; Remaining RST handling is common
endmac irqhandler
;**************************************************************************
@ -200,22 +200,22 @@ _ez80_handlers:
irqhandler 33 ; EZ80_PORTD5_IRQ 33 45 0x0f4
irqhandler 34 ; EZ80_PORTD6_IRQ 34 46 0x0f8
irqhandler 35 ; EZ80_PORTD7_IRQ 35 47 0x0fc
irqhandler EZ80_UNUSED+13 ; 48 0x100
irqhandler EZ80_UNUSED+14 ; 49 0x104
irqhandler EZ80_UNUSED+15 ; 50 0x108
irqhandler EZ80_UNUSED+16 ; 51 0x10c
irqhandler EZ80_UNUSED+17 ; 52 0x110
irqhandler EZ80_UNUSED+18 ; 53 0x114
irqhandler EZ80_UNUSED+19 ; 54 0x118
irqhandler EZ80_UNUSED+20 ; 55 0x11c
irqhandler EZ80_UNUSED+21 ; 56 0x120
irqhandler EZ80_UNUSED+22 ; 57 0x124
irqhandler EZ80_UNUSED+23 ; 58 0x128
irqhandler EZ80_UNUSED+24 ; 59 0x12c
irqhandler EZ80_UNUSED+25 ; 60 0x130
irqhandler EZ80_UNUSED+26 ; 61 0x134
irqhandler EZ80_UNUSED+27 ; 62 0x138
irqhandler EZ80_UNUSED+28 ; 63 0x13c
irqhandler EZ80_UNUSED+12 ; 48 0x100
irqhandler EZ80_UNUSED+13 ; 49 0x104
irqhandler EZ80_UNUSED+14 ; 50 0x108
irqhandler EZ80_UNUSED+15 ; 51 0x10c
irqhandler EZ80_UNUSED+16 ; 52 0x110
irqhandler EZ80_UNUSED+17 ; 53 0x114
irqhandler EZ80_UNUSED+18 ; 54 0x118
irqhandler EZ80_UNUSED+19 ; 55 0x11c
irqhandler EZ80_UNUSED+20 ; 56 0x120
irqhandler EZ80_UNUSED+21 ; 57 0x124
irqhandler EZ80_UNUSED+22 ; 58 0x128
irqhandler EZ80_UNUSED+23 ; 59 0x12c
irqhandler EZ80_UNUSED+24 ; 60 0x130
irqhandler EZ80_UNUSED+25 ; 61 0x134
irqhandler EZ80_UNUSED+26 ; 62 0x138
irqhandler EZ80_UNUSED+27 ; 63 0x13c
;**************************************************************************
; Vector Setup Logic

View File

@ -0,0 +1,352 @@
;**************************************************************************
; arch/z80/src/ez80/ez80f92_loader.asm
;
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; http://www.apache.org/licenses/LICENSE-2.0
;
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
;**************************************************************************
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref __vecstart
xref __vecend
xref _ez80_irq_common
;**************************************************************************
; Global Symbols Exported
;**************************************************************************
xdef _ez80_initvectors
;**************************************************************************
; Constants
;**************************************************************************
NVECTORS EQU 64 ; Max possible interrupt vectors
EZ80_UNUSED EQU 64 ; Denotes an unused vector
; RAM Memory map
;
; __vecstart Beginning of Interrupt Redirection information. This is
; used to hand off to RAM-based handlers for interrupts
; caught by FLASH interrupt vectors.
; __vecend End of the Interrupt Redirection information.
; __loaderstart Start of RAM used exclusively by the bootloader. This
; memory region an be recovered by the RAM-based program.
; __loaderend End of the bootloader RAM.
; __progstart Start of CODE for the RAM-based program. The program can
; freely use the memory region from _progstart-_progend and
; can recover the memory for _loaderstart-_loaderend for heap
; usage.
; __progend End of RAM/End of the RAM-based program
VECSTART EQU __vecstart ; Start of interrupt redirection area
VECSIZE EQU __vecend - __vecstart ; Size of interrupt redirection area
;**************************************************************************
; Macros
;**************************************************************************
; Define one interrupt handler
irqhandler: macro vectno
; Save AF on the stack, set the interrupt number and jump to the
; common reset handling logic.
; Offset 8: Return PC is already on the stack
push af ; Offset 7: AF (retaining flags)
ld a, #vectno ; A = vector number
jp _ez80_irq_common ; Remaining RST handling is common
endmac irqhandler
;**************************************************************************
; Vector Table
;**************************************************************************
; This segment must be aligned on a 256 byte boundary anywhere in RAM
; Each entry will be a 2-byte address in a 2-byte space. The vector table
; will always reside in FLASH memory; Only the loader in FLASH provides
; the vector table.
define .IVECTS, space = ROM, align = 100h
segment .IVECTS
; Vector table is a 2-bit address. The MSB is the I register; the LSB is
; the vector number. The vector table lies in FLASH. The addresses
; contained in the refers to an entry in the handler table that re-
; directs the interrupt to common interrupt handling logic.
_ez80_vectable:
dw _ez80_redirect + 0*_redirsize
dw _ez80_redirect + 1*_redirsize
dw _ez80_redirect + 2*_redirsize
dw _ez80_redirect + 3*_redirsize
dw _ez80_redirect + 4*_redirsize
dw _ez80_redirect + 5*_redirsize
dw _ez80_redirect + 6*_redirsize
dw _ez80_redirect + 7*_redirsize
dw _ez80_redirect + 8*_redirsize
dw _ez80_redirect + 9*_redirsize
dw _ez80_redirect + 10*_redirsize
dw _ez80_redirect + 11*_redirsize
dw _ez80_redirect + 12*_redirsize
dw _ez80_redirect + 13*_redirsize
dw _ez80_redirect + 14*_redirsize
dw _ez80_redirect + 15*_redirsize
dw _ez80_redirect + 16*_redirsize
dw _ez80_redirect + 17*_redirsize
dw _ez80_redirect + 18*_redirsize
dw _ez80_redirect + 19*_redirsize
dw _ez80_redirect + 20*_redirsize
dw _ez80_redirect + 21*_redirsize
dw _ez80_redirect + 22*_redirsize
dw _ez80_redirect + 23*_redirsize
dw _ez80_redirect + 24*_redirsize
dw _ez80_redirect + 25*_redirsize
dw _ez80_redirect + 26*_redirsize
dw _ez80_redirect + 27*_redirsize
dw _ez80_redirect + 28*_redirsize
dw _ez80_redirect + 29*_redirsize
dw _ez80_redirect + 30*_redirsize
dw _ez80_redirect + 31*_redirsize
dw _ez80_redirect + 32*_redirsize
dw _ez80_redirect + 33*_redirsize
dw _ez80_redirect + 34*_redirsize
dw _ez80_redirect + 35*_redirsize
dw _ez80_redirect + 36*_redirsize
dw _ez80_redirect + 37*_redirsize
dw _ez80_redirect + 38*_redirsize
dw _ez80_redirect + 39*_redirsize
dw _ez80_redirect + 40*_redirsize
dw _ez80_redirect + 41*_redirsize
dw _ez80_redirect + 42*_redirsize
dw _ez80_redirect + 43*_redirsize
dw _ez80_redirect + 44*_redirsize
dw _ez80_redirect + 45*_redirsize
dw _ez80_redirect + 46*_redirsize
dw _ez80_redirect + 47*_redirsize
dw _ez80_redirect + 48*_redirsize
dw _ez80_redirect + 49*_redirsize
dw _ez80_redirect + 50*_redirsize
dw _ez80_redirect + 51*_redirsize
dw _ez80_redirect + 52*_redirsize
dw _ez80_redirect + 53*_redirsize
dw _ez80_redirect + 54*_redirsize
dw _ez80_redirect + 55*_redirsize
dw _ez80_redirect + 56*_redirsize
dw _ez80_redirect + 57*_redirsize
dw _ez80_redirect + 58*_redirsize
dw _ez80_redirect + 59*_redirsize
dw _ez80_redirect + 60*_redirsize
dw _ez80_redirect + 61*_redirsize
dw _ez80_redirect + 62*_redirsize
dw _ez80_redirect + 63*_redirsize
;**************************************************************************
; Interrupt Redirection Table
;**************************************************************************
; Still in .IVECTS section
.assume ADL=1
; The redirection table is an intermediate step in interrupt processing.
; When the interrupt occurs, the address in the corresponding entry in the
; vector table (_ez80_vectable) will execute. That will be an entry in
; this table. That entry will simply to the handler entry which has been
; related in RAM at VECSTART. The reason for this redirection is so that
; RAM-based programs and receive the interrupts vectored through the ROM-
; based loader code.
_ez80_redirect:
jp VECSTART + 0*_handlersize
_redirsize EQU $-_ez80_redirect
jp VECSTART + 1*_handlersize
jp VECSTART + 2*_handlersize
jp VECSTART + 3*_handlersize
jp VECSTART + 4*_handlersize
jp VECSTART + 5*_handlersize
jp VECSTART + 6*_handlersize
jp VECSTART + 7*_handlersize
jp VECSTART + 8*_handlersize
jp VECSTART + 9*_handlersize
jp VECSTART + 10*_handlersize
jp VECSTART + 11*_handlersize
jp VECSTART + 12*_handlersize
jp VECSTART + 13*_handlersize
jp VECSTART + 14*_handlersize
jp VECSTART + 15*_handlersize
jp VECSTART + 16*_handlersize
jp VECSTART + 17*_handlersize
jp VECSTART + 18*_handlersize
jp VECSTART + 19*_handlersize
jp VECSTART + 20*_handlersize
jp VECSTART + 21*_handlersize
jp VECSTART + 22*_handlersize
jp VECSTART + 23*_handlersize
jp VECSTART + 24*_handlersize
jp VECSTART + 25*_handlersize
jp VECSTART + 26*_handlersize
jp VECSTART + 27*_handlersize
jp VECSTART + 28*_handlersize
jp VECSTART + 29*_handlersize
jp VECSTART + 30*_handlersize
jp VECSTART + 31*_handlersize
jp VECSTART + 32*_handlersize
jp VECSTART + 33*_handlersize
jp VECSTART + 34*_handlersize
jp VECSTART + 35*_handlersize
jp VECSTART + 36*_handlersize
jp VECSTART + 37*_handlersize
jp VECSTART + 38*_handlersize
jp VECSTART + 39*_handlersize
jp VECSTART + 40*_handlersize
jp VECSTART + 41*_handlersize
jp VECSTART + 42*_handlersize
jp VECSTART + 43*_handlersize
jp VECSTART + 44*_handlersize
jp VECSTART + 45*_handlersize
jp VECSTART + 46*_handlersize
jp VECSTART + 47*_handlersize
jp VECSTART + 48*_handlersize
jp VECSTART + 49*_handlersize
jp VECSTART + 50*_handlersize
jp VECSTART + 51*_handlersize
jp VECSTART + 52*_handlersize
jp VECSTART + 53*_handlersize
jp VECSTART + 54*_handlersize
jp VECSTART + 55*_handlersize
jp VECSTART + 56*_handlersize
jp VECSTART + 57*_handlersize
jp VECSTART + 58*_handlersize
jp VECSTART + 59*_handlersize
jp VECSTART + 60*_handlersize
jp VECSTART + 61*_handlersize
jp VECSTART + 62*_handlersize
jp VECSTART + 63*_handlersize
;**************************************************************************
; Interrupt Vector Handlers
;**************************************************************************
define .STARTUP, space = ROM
segment .STARTUP
.assume ADL=1
; This is a copy of the handler table that will be copied into RAM at the
; address given by VECSTART by _ez80_initvectors. FLASH based interrupt
; handling will vector here to support interrupts in the RAM-based program.
; Symbol Val VecNo Addr
;----------------- --- ----- -----
_ez80_handlers:
irqhandler EZ80_UNUSED ; 0 0x040
_handlersize EQU $-_ez80_handlers
irqhandler EZ80_UNUSED+1 ; 1 0x044
irqhandler EZ80_UNUSED+2 ; 2 0x045
irqhandler EZ80_UNUSED+3 ; 3 0x04c
irqhandler 0 ; EZ80_FLASH_IRQ 0 4 0x050
irqhandler 1 ; EZ80_TIMER0_IRQ 1 5 0x054
irqhandler 2 ; EZ80_TIMER1_IRQ 2 6 0x058
irqhandler 3 ; EZ80_TIMER2_IRQ 3 7 0x05c
irqhandler 4 ; EZ80_TIMER3_IRQ 4 8 0x060
irqhandler 5 ; EZ80_TIMER4_IRQ 5 9 0x064
irqhandler 6 ; EZ80_TIMER5_IRQ 6 10 0x068
irqhandler 7 ; EZ80_RTC_IRQ 7 11 0x06C
irqhandler 8 ; EZ80_UART0_IRQ 8 12 0x070
irqhandler 9 ; EZ80_UART1_IRQ 9 13 0x074
irqhandler 10 ; EZ80_I2C_IRQ 10 14 0x078
irqhandler 11 ; EZ80_SPI_IRQ 11 15 0x07c
irqhandler EZ80_UNUSED+4 ; 16 0x080
irqhandler EZ80_UNUSED+5 ; 17 0x084
irqhandler EZ80_UNUSED+6 ; 18 0x088
irqhandler EZ80_UNUSED+7 ; 19 0x08c
irqhandler EZ80_UNUSED+8 ; 16 0x080
irqhandler EZ80_UNUSED+9 ; 17 0x094
irqhandler EZ80_UNUSED+10 ; 18 0x098
irqhandler EZ80_UNUSED+11 ; 19 0x09c
irqhandler 12 ; EZ80_PORTB0_IRQ 12 24 0x0a0
irqhandler 13 ; EZ80_PORTB1_IRQ 13 25 0x0a4
irqhandler 14 ; EZ80_PORTB2_IRQ 14 26 0x0a8
irqhandler 15 ; EZ80_PORTB3_IRQ 15 27 0x0ac
irqhandler 16 ; EZ80_PORTB4_IRQ 16 28 0x0b0
irqhandler 17 ; EZ80_PORTB5_IRQ 17 29 0x0b4
irqhandler 18 ; EZ80_PORTB6_IRQ 18 20 0x0b8
irqhandler 19 ; EZ80_PORTB7_IRQ 19 21 0x0bc
irqhandler 20 ; EZ80_PORTC0_IRQ 20 22 0x0c0
irqhandler 21 ; EZ80_PORTC1_IRQ 21 23 0x0c4
irqhandler 22 ; EZ80_PORTC2_IRQ 22 24 0x0c8
irqhandler 23 ; EZ80_PORTC3_IRQ 23 25 0x0cc
irqhandler 24 ; EZ80_PORTC4_IRQ 24 26 0x0d0
irqhandler 25 ; EZ80_PORTC5_IRQ 25 27 0x0d4
irqhandler 26 ; EZ80_PORTC6_IRQ 26 28 0x0d8
irqhandler 27 ; EZ80_PORTC7_IRQ 27 29 0x0dc
irqhandler 28 ; EZ80_PORTD0_IRQ 28 40 0x0e0
irqhandler 29 ; EZ80_PORTD1_IRQ 29 41 0x0e4
irqhandler 30 ; EZ80_PORTD2_IRQ 30 42 0x0e8
irqhandler 31 ; EZ80_PORTD3_IRQ 31 43 0x0ec
irqhandler 32 ; EZ80_PORTD4_IRQ 32 44 0x0f0
irqhandler 33 ; EZ80_PORTD5_IRQ 33 45 0x0f4
irqhandler 34 ; EZ80_PORTD6_IRQ 34 46 0x0f8
irqhandler 35 ; EZ80_PORTD7_IRQ 35 47 0x0fc
irqhandler EZ80_UNUSED+12 ; 48 0x100
irqhandler EZ80_UNUSED+13 ; 49 0x104
irqhandler EZ80_UNUSED+14 ; 50 0x108
irqhandler EZ80_UNUSED+15 ; 51 0x10c
irqhandler EZ80_UNUSED+16 ; 52 0x110
irqhandler EZ80_UNUSED+17 ; 53 0x114
irqhandler EZ80_UNUSED+18 ; 54 0x118
irqhandler EZ80_UNUSED+19 ; 55 0x11c
irqhandler EZ80_UNUSED+20 ; 56 0x120
irqhandler EZ80_UNUSED+21 ; 57 0x124
irqhandler EZ80_UNUSED+22 ; 58 0x128
irqhandler EZ80_UNUSED+23 ; 59 0x12c
irqhandler EZ80_UNUSED+24 ; 60 0x130
irqhandler EZ80_UNUSED+25 ; 61 0x134
irqhandler EZ80_UNUSED+26 ; 62 0x138
irqhandler EZ80_UNUSED+27 ; 63 0x13c
_copysize EQU $-_ez80_handlers
;**************************************************************************
; Vector Setup Logic
;**************************************************************************
; Still in the .STARTUP segment.
_ez80_initvectors:
; The interrupt vector and redirection tables reside in FLASH, but the
; handlers must be copied to into the VECSTART region in RAM. This
; is necessary to support interrupt hand-off from FLASH-based interrupt
; vectors to RAM-based programs.
; Copy the initialized data section
ld bc, _copysize ; [bc] = data length
ld hl, _ez80_handlers ; [hl] = data source
ld de, VECSTART ; [de] = data destination
ldir ; Copy the interrupt handlers
; Select interrupt mode 2
im 2 ; Interrupt mode 2
; Write the address of the vector table into the interrupt vector base
ld a, _ez80_vectable >> 8 & 0ffh
ld i, a
ret
end

View File

@ -0,0 +1,183 @@
;**************************************************************************
; arch/z80/src/ez80/ez80f92_handlers.asm
;
; Licensed to the Apache Software Foundation (ASF) under one or more
; contributor license agreements. See the NOTICE file distributed with
; this work for additional information regarding copyright ownership. The
; ASF licenses this file to you under the Apache License, Version 2.0 (the
; "License"); you may not use this file except in compliance with the
; License. You may obtain a copy of the License at
;
; http://www.apache.org/licenses/LICENSE-2.0
;
; Unless required by applicable law or agreed to in writing, software
; distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
; WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
; License for the specific language governing permissions and limitations
; under the License.
;
;**************************************************************************
;**************************************************************************
; Global Symbols Imported
;**************************************************************************
xref __vecstart
xref __vecend
xref _ez80_irq_common
;**************************************************************************
; Global Symbols Exported
;**************************************************************************
xdef _ez80_initvectors
;**************************************************************************
; Constants
;**************************************************************************
NVECTORS EQU 64 ; Max possible interrupt vectors
EZ80_UNUSED EQU 64 ; Denotes an unused vector
; RAM Memory map
;
; __vecstart Beginning of Interrupt Redirection information. This is
; used to hand off to RAM-based handlers for interrupts
; caught by FLASH interrupt vectors.
; __vecend End of the Interrupt Redirection information.
; __loaderstart Start of RAM used exclusively by the bootloader. This
; memory region an be recovered by the RAM-based program.
; __loaderend End of the bootloader RAM.
; __progstart Start of CODE for the RAM-based program. The program can
; freely use the memory region from _progstart-_progend and
; can recover the memory for _loaderstart-_loaderend for heap
; usage.
; __progend End of RAM/End of the RAM-based program
VECSTART EQU __vecstart ; Start of interrupt redirection area
VECSIZE EQU __vecend - __vecstart ; Size of interrupt redirection area
;**************************************************************************
; Macros
;**************************************************************************
; Define one interrupt handler
irqhandler: macro vectno
; Save AF on the stack, set the interrupt number and jump to the
; common reset handling logic.
; Offset 8: Return PC is already on the stack
push af ; Offset 7: AF (retaining flags)
ld a, #vectno ; A = vector number
jp _ez80_irq_common ; Remaining RST handling is common
endmac irqhandler
;**************************************************************************
; Interrupt Vector Handlers
;**************************************************************************
define .STARTUP, space = ROM
segment .STARTUP
.assume ADL=1
; This is a copy of the handler table that will be copied into RAM at the
; address given by VECSTART by _ez80_initvectors. FLASH based interrupt
; handling will vector here to support interrupts in the RAM-based program.
; Symbol Val VecNo Addr
;----------------- --- ----- -----
_ez80_handlers:
irqhandler EZ80_UNUSED ; 0 0x040
_handlersize EQU $-_ez80_handlers
irqhandler EZ80_UNUSED+1 ; 1 0x044
irqhandler EZ80_UNUSED+2 ; 2 0x045
irqhandler EZ80_UNUSED+3 ; 3 0x04c
irqhandler 0 ; EZ80_FLASH_IRQ 0 4 0x050
irqhandler 1 ; EZ80_TIMER0_IRQ 1 5 0x054
irqhandler 2 ; EZ80_TIMER1_IRQ 2 6 0x058
irqhandler 3 ; EZ80_TIMER2_IRQ 3 7 0x05c
irqhandler 4 ; EZ80_TIMER3_IRQ 4 8 0x060
irqhandler 5 ; EZ80_TIMER4_IRQ 5 9 0x064
irqhandler 6 ; EZ80_TIMER5_IRQ 6 10 0x068
irqhandler 7 ; EZ80_RTC_IRQ 7 11 0x06C
irqhandler 8 ; EZ80_UART0_IRQ 8 12 0x070
irqhandler 9 ; EZ80_UART1_IRQ 9 13 0x074
irqhandler 10 ; EZ80_I2C_IRQ 10 14 0x078
irqhandler 11 ; EZ80_SPI_IRQ 11 15 0x07c
irqhandler EZ80_UNUSED+4 ; 16 0x080
irqhandler EZ80_UNUSED+5 ; 17 0x084
irqhandler EZ80_UNUSED+6 ; 18 0x088
irqhandler EZ80_UNUSED+7 ; 19 0x08c
irqhandler EZ80_UNUSED+8 ; 16 0x080
irqhandler EZ80_UNUSED+9 ; 17 0x094
irqhandler EZ80_UNUSED+10 ; 18 0x098
irqhandler EZ80_UNUSED+11 ; 19 0x09c
irqhandler 12 ; EZ80_PORTB0_IRQ 12 24 0x0a0
irqhandler 13 ; EZ80_PORTB1_IRQ 13 25 0x0a4
irqhandler 14 ; EZ80_PORTB2_IRQ 14 26 0x0a8
irqhandler 15 ; EZ80_PORTB3_IRQ 15 27 0x0ac
irqhandler 16 ; EZ80_PORTB4_IRQ 16 28 0x0b0
irqhandler 17 ; EZ80_PORTB5_IRQ 17 29 0x0b4
irqhandler 18 ; EZ80_PORTB6_IRQ 18 20 0x0b8
irqhandler 19 ; EZ80_PORTB7_IRQ 19 21 0x0bc
irqhandler 20 ; EZ80_PORTC0_IRQ 20 22 0x0c0
irqhandler 21 ; EZ80_PORTC1_IRQ 21 23 0x0c4
irqhandler 22 ; EZ80_PORTC2_IRQ 22 24 0x0c8
irqhandler 23 ; EZ80_PORTC3_IRQ 23 25 0x0cc
irqhandler 24 ; EZ80_PORTC4_IRQ 24 26 0x0d0
irqhandler 25 ; EZ80_PORTC5_IRQ 25 27 0x0d4
irqhandler 26 ; EZ80_PORTC6_IRQ 26 28 0x0d8
irqhandler 27 ; EZ80_PORTC7_IRQ 27 29 0x0dc
irqhandler 28 ; EZ80_PORTD0_IRQ 28 40 0x0e0
irqhandler 29 ; EZ80_PORTD1_IRQ 29 41 0x0e4
irqhandler 30 ; EZ80_PORTD2_IRQ 30 42 0x0e8
irqhandler 31 ; EZ80_PORTD3_IRQ 31 43 0x0ec
irqhandler 32 ; EZ80_PORTD4_IRQ 32 44 0x0f0
irqhandler 33 ; EZ80_PORTD5_IRQ 33 45 0x0f4
irqhandler 34 ; EZ80_PORTD6_IRQ 34 46 0x0f8
irqhandler 35 ; EZ80_PORTD7_IRQ 35 47 0x0fc
irqhandler EZ80_UNUSED+12 ; 48 0x100
irqhandler EZ80_UNUSED+13 ; 49 0x104
irqhandler EZ80_UNUSED+14 ; 50 0x108
irqhandler EZ80_UNUSED+15 ; 51 0x10c
irqhandler EZ80_UNUSED+16 ; 52 0x110
irqhandler EZ80_UNUSED+17 ; 53 0x114
irqhandler EZ80_UNUSED+18 ; 54 0x118
irqhandler EZ80_UNUSED+19 ; 55 0x11c
irqhandler EZ80_UNUSED+20 ; 56 0x120
irqhandler EZ80_UNUSED+21 ; 57 0x124
irqhandler EZ80_UNUSED+22 ; 58 0x128
irqhandler EZ80_UNUSED+23 ; 59 0x12c
irqhandler EZ80_UNUSED+24 ; 60 0x130
irqhandler EZ80_UNUSED+25 ; 61 0x134
irqhandler EZ80_UNUSED+26 ; 62 0x138
irqhandler EZ80_UNUSED+27 ; 63 0x13c
_copysize EQU $-_ez80_handlers
;**************************************************************************
; Vector Setup Logic
;**************************************************************************
; Still in the .STARTUP segment.
_ez80_initvectors:
; The interrupt vector and redirection tables reside in FLASH, but the
; handlers must be copied to into the VECSTART region in RAM. This
; is necessary to support interrupt hand-off from FLASH-based interrupt
; vectors to RAM-based programs.
; Copy the initialized data section
ld bc, _copysize ; [bc] = data length
ld hl, _ez80_handlers ; [hl] = data source
ld de, VECSTART ; [de] = data destination
ldir ; Copy the interrupt handlers
; REVISIT: We must assume that the bootloader has configured the
; interrupt mode correctly. The IM register should be set to 2(i.e,
; interrupt mode 2) and the I register should be set according to the
; location of the 1st level interrupt vectors in FLASH.
ret
end

View File

@ -26,7 +26,6 @@ CONFIG_EXAMPLES_DHCPD_IPADDR=0x0a000001
CONFIG_EXAMPLES_DHCPD_NOMAC=y
CONFIG_EZ80_EMAC=y
CONFIG_EZ80_PHYCONFIG=1
CONFIG_EZ80_RAMADDR=0xf7c000
CONFIG_EZ80_UART0=y
CONFIG_HOST_WINDOWS=y
CONFIG_MAX_TASKS=8

View File

@ -22,7 +22,6 @@ CONFIG_ETH0_PHY_AM79C874=y
CONFIG_EXAMPLES_WEBSERVER=y
CONFIG_EZ80_EMAC=y
CONFIG_EZ80_PHYCONFIG=1
CONFIG_EZ80_RAMADDR=0xf7c000
CONFIG_EZ80_UART0=y
CONFIG_HOST_WINDOWS=y
CONFIG_MAX_TASKS=8

View File

@ -24,7 +24,6 @@ CONFIG_EXAMPLES_NETTEST=y
CONFIG_EXAMPLES_NETTEST_NOMAC=y
CONFIG_EZ80_EMAC=y
CONFIG_EZ80_PHYCONFIG=1
CONFIG_EZ80_RAMADDR=0xf7c000
CONFIG_EZ80_UART0=y
CONFIG_HOST_WINDOWS=y
CONFIG_MAX_TASKS=8

View File

@ -20,7 +20,6 @@ CONFIG_DISABLE_MQUEUE=y
CONFIG_ETH0_PHY_AM79C874=y
CONFIG_EZ80_EMAC=y
CONFIG_EZ80_PHYCONFIG=1
CONFIG_EZ80_RAMADDR=0xf7c000
CONFIG_EZ80_UART0=y
CONFIG_HOST_WINDOWS=y
CONFIG_MAX_TASKS=16

View File

@ -23,7 +23,6 @@ CONFIG_EXAMPLES_POLL=y
CONFIG_EXAMPLES_POLL_NOMAC=y
CONFIG_EZ80_EMAC=y
CONFIG_EZ80_PHYCONFIG=1
CONFIG_EZ80_RAMADDR=0xf7c000
CONFIG_EZ80_UART0=y
CONFIG_HOST_WINDOWS=y
CONFIG_MAX_TASKS=8

View File

@ -27,6 +27,7 @@ config MAKERLISP_COPYTORAM
config MAKERLISP_SDBOOT
bool "Build SD boot loader"
default n
select EZ80_BOOTLOADER
---help---
Select this option only with the boards/makerlisp/sdboot
configuration. This will enable the components needed only by the

View File

@ -5,11 +5,6 @@
if ARCH_BOARD_Z20X
config Z20X_BOOTLOADER
bool
default n
select BOOT_RUNFROMFLASH
choice
prompt "Build selection"
default Z20X_PROGRAM
@ -17,7 +12,7 @@ choice
config Z20X_SDBOOT
bool "SD boot loader"
select LIB_HEX2BIN
select Z20X_BOOTLOADER
select EZ80_BOOTLOADER
depends on EZ80_SPI && MMCSD_SPI
---help---
Select this option only with the boards/z20x/sdboot
@ -28,7 +23,7 @@ config Z20X_W25BOOT
bool "W25 boot loader"
select Z20X_W25_CHARDEV
select LIB_HEX2BIN
select Z20X_BOOTLOADER
select EZ80_BOOTLOADER
depends on EZ80_SPI && MTD_W25
---help---
Select this option only with the boards/z20x/w25boot
@ -37,7 +32,7 @@ config Z20X_W25BOOT
config Z20X_PROGRAM
bool "Loadable program"
select CONFIG_BOOT_RUNFROMEXTSRAM
select EZ80_PROGRAM
---help---
Normal program that resides on SD card or in W25 FLASH and is
loaded into RAM by a bootloader.

View File

@ -25,7 +25,6 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FS_FAT=y
CONFIG_HOST_WINDOWS=y
CONFIG_LIB_HEX2BIN=y
CONFIG_MAX_TASKS=8
CONFIG_MAX_WDOGPARMS=2
CONFIG_MMCSD=y

View File

@ -1,6 +1,6 @@
sdboot.hex
sdboot.map
sdboot.lod
sdboot.wsp
w25boot.hex
w25boot.map
w25boot.lod
w25boot.wsp
*.asm
Debug

View File

@ -68,12 +68,12 @@ ARFLAGS = -quiet -warn
#
# Possible configurations
#
# 1. FLASH-resident bootloader (CONFIG_Z20X_BOOTLOADER)
# 1. FLASH-resident bootloader (CONFIG_EZ80_BOOTLOADER)
# 2. RAM-resident applications loaded by bootloader (CONFIG_Z20X_PROGRAM)
# 3. FLASH-resident, standalone program (CONFIG_Z20X_STANDALONE)
# 4. FLASH-resident, standalone copy-to-RAM program (CONFIG_Z20X_COPYTORAM)
ifeq ($(CONFIG_Z20X_BOOTLOADER),y)
ifeq ($(CONFIG_EZ80_BOOTLOADER),y)
LDSCRIPT = z20x_loader.linkcmd
else ifeq ($(CONFIG_Z20X_PROGRAM),y)
LDSCRIPT = z20x_program.linkcmd

View File

@ -48,7 +48,8 @@ DEFINE __copy_code_to_ram = 0
DEFINE __crtl = 1
DEFINE __vecstart = $040000
DEFINE __loaderstart = $040400
DEFINE __vecend = $0401ff
DEFINE __loaderstart = $040200
DEFINE __loaderend = $04ffff
DEFINE __progstart = $050000
DEFINE __progend = $0bffff

View File

@ -34,7 +34,7 @@ CHANGE TEXT is CODE
CHANGE CODE is RAM
CHANGE STRSECT is CODE
ORDER .RESET,.IVECTS,.STARTUP,CODE,DATA
ORDER .RESET,.STARTUP,CODE,DATA
DEFINE __low_romdata = copy base of DATA
DEFINE __low_data = base of DATA
@ -51,7 +51,8 @@ DEFINE __copy_code_to_ram = 0
DEFINE __crtl = 1
DEFINE __vecstart = $040000
DEFINE __loaderstart = $040400
DEFINE __vecend = $0401ff
DEFINE __loaderstart = $040200
DEFINE __loaderend = $04ffff
DEFINE __progstart = $050000
DEFINE __progend = $0bffff

View File

@ -27,6 +27,7 @@
#include <stdbool.h>
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
#include <nuttx/mm/mm.h>
#include <arch/chip/io.h>

View File

@ -93,11 +93,13 @@
/* RAM Memory map
*
* 040000 Beginning of RAM
* 040000 _vecstart Beginning of Vector information. Used to hand off
* to RAM-based handlers for interrupts caught by
* FLASH interrupt vectors. 1Kb is set aside for RAM-
* based interrupt handling information.
* 040400 _loaderstart Start of RAM used exclusively by the bootloader.
* 040000 _vecstart Beginning of Interrupt Redirection information. This
* is used to hand off to RAM-based handlers for
* interrupts caught by FLASH interrupt vectors. 512b is
* set aside for RAM-based interrupt handling
* information.
* 0401ff _vecend End of the Interrupt Redirection information.
* 040200 _loaderstart Start of RAM used exclusively by the bootloader.
* This memory region an be recovered by the RAM-based
* program.
* 04ffff _loaderend
@ -111,12 +113,19 @@
extern unsigned long _vecstart;
#define VECSTART ((uintptr_t)&_vecstart)
extern unsigned long _vecend;
#define VECEND ((uintptr_t)&_vecend)
#define VECSIZE (VECEND - VECSTART + 1)
extern unsigned long _loaderstart;
#define LOADERSTART ((uintptr_t)&_loaderstart)
extern unsigned long _loaderend;
#define LOADEREND ((uintptr_t)&_loaderend)
#define LOADERSIZE (LOADEREND - LOADERSTART + 1)
extern unsigned long _progstart;
#define PROGSTART ((uintptr_t)&_progstart)

View File

@ -1,5 +1,5 @@
/****************************************************************************
* libs/libc/misc/lib_err.c
* libs/libc/misc/lib_debug.c
*
* Copyright (C) 2007-2009, 2011-2012, 2016, 2018-2019 Gregory Nutt. All
* rights reserved.