From dd3dedf14c0a7949f15aa207906764586419e531 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 8 Feb 2009 22:52:08 +0000 Subject: M16C chip support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1484 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/sh/src/m16c/Make.defs | 51 +++++ nuttx/arch/sh/src/m16c/README.txt | 2 + nuttx/arch/sh/src/m16c/chip.h | 235 ++++++++++++++++++++++ nuttx/arch/sh/src/m16c/m16c_head.S | 393 +++++++++++++++++++++++++++++++++++++ 4 files changed, 681 insertions(+) create mode 100644 nuttx/arch/sh/src/m16c/Make.defs create mode 100644 nuttx/arch/sh/src/m16c/README.txt create mode 100644 nuttx/arch/sh/src/m16c/chip.h create mode 100644 nuttx/arch/sh/src/m16c/m16c_head.S (limited to 'nuttx/arch/sh') diff --git a/nuttx/arch/sh/src/m16c/Make.defs b/nuttx/arch/sh/src/m16c/Make.defs new file mode 100644 index 000000000..7c1645c8b --- /dev/null +++ b/nuttx/arch/sh/src/m16c/Make.defs @@ -0,0 +1,51 @@ +############################################################################## +# arch/sh/src/m16c/Make.defs +# +# Copyright (C) 2009 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################## + +HEAD_ASRC = m16c_head.S + +CMN_ASRCS = +CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ + up_createstack.c up_doirq.c up_exit.c up_idle.c up_initialize.c \ + up_initialstate.c up_interruptcontext.c up_lowputs.c \ + up_mdelay.c up_puts.c up_releasepending.c up_releasestack.c \ + up_reprioritizertr.c up_udelay.c up_unblocktask.c up_usestack.c + +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c +endif + +#CHIP_ASRCS = m16c_vector.S m16c_saveusercontext.S +#CHIP_CSRCS = m16c_lowputc.c m16c_irq.c m16c_timerisr.c m16c_serial.c + diff --git a/nuttx/arch/sh/src/m16c/README.txt b/nuttx/arch/sh/src/m16c/README.txt new file mode 100644 index 000000000..16e6c4717 --- /dev/null +++ b/nuttx/arch/sh/src/m16c/README.txt @@ -0,0 +1,2 @@ +This directory contains source files that are unique to the M16C +chip architecture. diff --git a/nuttx/arch/sh/src/m16c/chip.h b/nuttx/arch/sh/src/m16c/chip.h new file mode 100644 index 000000000..580823f1b --- /dev/null +++ b/nuttx/arch/sh/src/m16c/chip.h @@ -0,0 +1,235 @@ +/************************************************************************************ + * arch/sh/src/m16c/chip.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_SH_SRC_M16C_CHIP_H +#define __ARCH_SH_SRC_M16C_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Memory Map */ + +/* Memory-mapped special function registers begin at address 0x00000 */ + +#define M16C_SFR_BASE 0x00000 /* 00000-003ff: Special Function Registers */ + +/* Internal, on-chip SRAM begins at address 0x00400 for all chips, regardless of the + * size of the on-chip SRAM. + */ + +#define M16C_IRAM_BASE 0x00400 /* 00400-00xxx: Internal RAM */ +#if defined(CONFIG_ARCH_CHIP_M30262F3) || defined(CONFIG_ARCH_CHIP_M30262F4) +# define M16C_IRAM_END 0x007ff /* End+1 address of internal RAM */ + /* 00800-0efff: Reserved */ +#elif defined(CONFIG_ARCH_CHIP_M30262F6) || defined(CONFIG_ARCH_CHIP_M30262F8) +# define M16C_IRAM_END 0x00bff /* End+1 address of internal RAM */ + /* 00c00-0efff: Reserved */ +#endif + +/* Two banks of virtual EEPROM (all parts) */ + +#define M16C_VEEPROM1_BASE 0x0f000 /* 0f000-0f7fff: Virtual EEPPROM block 1 */ +#define M16C_VEEPROM2_BASE 0x0f800 /* 0f800-0fffff: Virtual EEPPROM block 2 */ + +/* If there were external, "far" RAM, it would be begin at 0x10000. However, these + * specific chips do not support external RAM. + */ + +/* Each part has a different amount on on-chip FLASH. The ending FLASH address is + * 0xfffff for all chips, but the starting address varies depening on the amount + * of on-chip FLASH. + */ + +#if defined(CONFIG_ARCH_CHIP_M30262F3) + /* 10000-f9ffff: Reserved */ +# define M16C_FLASH_BASE 0xfa000 /* fa000-ffffff: Flash ROM (M30262F8) */ +#elif defined(CONFIG_ARCH_CHIP_M30262F4) + /* 10000-f7ffff: Reserved */ +# define M16C_FLASH_BASE 0xf8000 /* f8000-ffffff: Flash ROM (M30262F8) */ +#elif defined(CONFIG_ARCH_CHIP_M30262F6) + /* 10000-f3ffff: Reserved */ +# define M16C_FLASH_BASE 0xf4000 /* f4000-ffffff: Flash ROM (M30262F8) */ +#elif defined(CONFIG_ARCH_CHIP_M30262F8) + /* 10000-efffff: Reserved */ +# define M16C_FLASH_BASE 0xf0000 /* f0000-ffffff: Flash ROM (M30262F8) */ +#endif + +/* Special Function Register Addresses */ + +#define M16C_PM0 0x00004 /* Processor mode 0 */ +#define M16C_PM1 0x00005 /* Processor mode 1 */ +#define M16C_CM0 0x00006 /* System clock control 0 */ +#define M16C_CM1 0x00007 /* System clock control 1 */ +#define M16C_AIER 0x00009 /* Addrese match interrupt enable */ +#define M16C_PRCR 0x0000a /* Protect */ +#define M16C_CM2 0x0000c /* Oscillation stop detection */ +#define M16C_WDTS 0x0000e /* Watchdog timer start */ +#define M16C_WDC 0x0000f /* Watchdog timer control */ +#define M16C_RMAD0 0x00010 /* Address match interrupt 0 */ +#define M16C_RMAD1 0x00014 /* Address match interrupt 1 */ +#define M16C_VCR1 0x00019 /* Power supply detection 1 */ +#define M16C_VCR2 0x0001a /* Power supply detection 2 */ +#define M16C_PM2 0x0001e /* Processor mode 2 */ +#define M16C_D4INT 0x0001f /* Power supply 4V detection */ +#define M16C_SAR0 0x00020 /* DMA0 source pointer */ +#define M16C_DAR0 0x00024 /* DMA0 destination pointer */ +#define M16C_TCR0 0x00028 /* DMA0 transfer counter */ +#define M16C_DM0CON 0x0002c /* DMA0 control */ +#define M16C_SAR1 0x00030 /* DMA1 source pointer */ +#define M16C_DAR1 0x00034 /* DMA1 destination pointer */ +#define M16C_TCR1 0x00038 /* DMA1 transfer counter */ +#define M16C_DM1CON 0x0003c /* DMA1 control */ +#define M16C_INT3IC 0x00044 /* INT3 interrupt control */ +#define M16C_INT5IC 0x00048 /* INT5 interrupt control */ +#define M16C_INT4IC 0x00049 /* INT4 interrupt control */ +#define M16C_BCNIC 0x0004a /* Bus collision detection interrupt control */ +#define M16C_DM0IC 0x0004b /* DMA0 interrupt control */ +#define M16C_DM1IC 0x0004c /* DMA1 interrupt control */ +#define M16C_KUPIC 0x0004d /* Key input interrupt control */ +#define M16C_ADIC 0x0004e /* A-D conversion interrupt control */ +#define M16C_S2TIC 0x0004f /* UART2 transmit interrupt control */ +#define M16C_S2RIC 0x00050 /* UART2 receive interrupt control */ +#define M16C_S0TIC 0x00051 /* UART0 transmit interrupt control */ +#define M16C_S0RIC 0x00052 /* UART0 receive interrupt control */ +#define M16C_S1TIC 0x00053 /* UART1 transmit interrupt control */ +#define M16C_S1RIC 0x00054 /* UART1 receive interrupt control */ +#define M16C_TA0IC 0x00055 /* Timer A0 interrupt control */ +#define M16C_TA1IC 0x00056 /* Timer A1 interrupt control */ +#define M16C_TA2IC 0x00057 /* Timer A2 interrupt control */ +#define M16C_TA3IC 0x00058 /* Timer A3 interrupt control */ +#define M16C_TA4IC 0x00059 /* Timer A4 interrupt control */ +#define M16C_TB0IC 0x0005a /* Timer B0 interrupt control */ +#define M16C_TB1IC 0x0005b /* Timer B1 interrupt control */ +#define M16C_TB2IC 0x0005c /* Timer B2 interrupt control */ +#define M16C_INT0IC 0x0005d /* INT0 interrupt control */ +#define M16C_INT1IC 0x0005e /* INT1 interrupt control */ +#define M16C_FMR4 0x001b3 /* Flash Control 4 */ +#define M16C_FMR1 0x001b5 /* Flash Control 1 */ +#define M16C_FMR0 0x001b7 /* Flash Control 0 */ +#define M16C_PCLKR 0x0025e /* Peripheral Clock Select */ +#define M16C_TA11 0x00342 /* Timer A1-1 */ +#define M16C_TA21 0x00344 /* Timer A2-1 */ +#define M16C_TA41 0x00346 /* Timer A4-1 */ +#define M16C_INVC0 0x00348 /* Three-phase PWM control 0 */ +#define M16C_INVC1 0x00349 /* Three-phase PWM control 1 */ +#define M16C_IDB0 0x0034a /* Three-phase output buffer 0 */ +#define M16C_IDB1 0x0034b /* Three-phase output buffer 1 */ +#define M16C_DTT 0x0034c /* Dead time timer */ +#define M16C_ICTB2 0x0034d /* Timer B2 interrupt occurences frequency set counter */ +#define M16C_IFSR 0x0035f /* Interrupt request cause select */ +#define M16C_U2SMR4 0x00374 /* UART2 special mode register4 */ +#define M16C_U2SMR3 0x00375 /* UART2 special mode register3 */ +#define M16C_U2SMR2 0x00376 /* UART2 special mode register2 */ +#define M16C_U2SMR 0x00377 /* UART2 special mode */ +#define M16C_U2MR 0x00378 /* UART2 transmit/receive mode */ +#define M16C_U2BRG 0x00379 /* UART2 bit rate generator */ +#define M16C_U2TB 0x0037a /* UART2 transmit buffer */ +#define M16C_U2C0 0x0037c /* UART2 transmit/receive control 0 */ +#define M16C_U2C1 0x0037d /* UART2 transmit/receive control 1 */ +#define M16C_U2RB 0x0037e /* UART2 receive buffer */ +#define M16C_TABSR 0x00380 /* Count start flag */ +#define M16C_CPSRF 0x00381 /* Clock prescaler reset flag */ +#define M16C_ONSF 0x00382 /* One-shot start flag */ +#define M16C_TRGSR 0x00383 /* Trigger select */ +#define M16C_UDF 0x00384 /* Up-down flag */ +#define M16C_TA0 0x00386 /* Timer A0 */ +#define M16C_TA1 0x00388 /* Timer A1 */ +#define M16C_TA2 0x0038a /* Timer A2 */ +#define M16C_TA3 0x0038c /* Timer A3 */ +#define M16C_TA4 0x0038e /* Timer A4 */ +#define M16C_TB0 0x00390 /* Timer B0 */ +#define M16C_TB1 0x00392 /* Timer B1 */ +#define M16C_TB2 0x00394 /* Timer B2 */ +#define M16C_TA0MR 0x00396 /* Timer A0 mode */ +#define M16C_TA1MR 0x00397 /* Timer A1 mode */ +#define M16C_TA2MR 0x00398 /* Timer A2 mode */ +#define M16C_TA3MR 0x00399 /* Timer A3 mode */ +#define M16C_TA4MR 0x0039a /* Timer A4 mode */ +#define M16C_TB0MR 0x0039b /* Timer B0 mode */ +#define M16C_TB1MR 0x0039c /* Timer B1 mode */ +#define M16C_TB2MR 0x0039d /* Timer B2 mode */ +#define M16C_TB2SC 0x0039e /* Timer B2 special mode */ +#define M16C_U0MR 0x003a0 /* UART0 transmit/receive mode */ +#define M16C_U0BRG 0x003a1 /* UART0 bit rate generator */ +#define M16C_U0TB 0x003a2 /* UART0 transmit buffer */ +#define M16C_U0C0 0x003a4 /* UART0 transmit/receive control 0 */ +#define M16C_U0C1 0x003a5 /* UART0 transmit/receive control 1 */ +#define M16C_U0RB 0x003a6 /* UART0 receive buffer */ +#define M16C_U1MR 0x003a8 /* UART1 transmit/receive mode */ +#define M16C_U1BRG 0x003a9 /* UART1 bit rate generator */ +#define M16C_U1TB 0x003aa /* UART1 transmit buffer */ +#define M16C_U1C0 0x003ac /* UART1 transmit/receive control 0 */ +#define M16C_U1C1 0x003ad /* UART1 transmit/receive control 1 */ +#define M16C_U1RB 0x003ae /* UART1 receive buffer */ +#define M16C_UCON 0x003b0 /* UART2 transmit/receive control 2 */ +#define M16C_DM0SL 0x003b8 /* DMA0 cause select */ +#define M16C_DM1SL 0x003ba /* DMA1 cause select */ +#define M16C_AD0 0x003c0 /* A-D 0 */ +#define M16C_AD1 0x003c2 /* A-D 1 */ +#define M16C_AD2 0x003c4 /* A-D 2 */ +#define M16C_AD3 0x003c6 /* A-D 3 */ +#define M16C_AD4 0x003c8 /* A-D 4 */ +#define M16C_AD5 0x003ca /* A-D 5 */ +#define M16C_AD6 0x003cc /* A-D 6 */ +#define M16C_AD7 0x003ce /* A-D 7 */ +#define M16C_ADCON2 0x003d4 /* A-D control 2 */ +#define M16C_ADCON0 0x003d6 /* A-D control 0 */ +#define M16C_ADCON1 0x003d7 /* A-D control 1 */ +#define M16C_P1 0x003e1 /* Port P1 */ +#define M16C_PD1 0x003e3 /* Port P1 direction */ +#define M16C_P6 0x003ec /* Port P6 */ +#define M16C_P7 0x003ed /* Port P7 */ +#define M16C_PD6 0x003ee /* Port P6 direction */ +#define M16C_PD7 0x003ef /* Port P7 direction */ +#define M16C_P8 0x003f0 /* Port P8 */ +#define M16C_P9 0x003f1 /* Port P9 */ +#define M16C_PD8 0x003f2 /* Port P8 direction */ +#define M16C_PD9 0x003f3 /* Port P9 direction */ +#define M16C_P10 0x003f4 /* Port P10 */ +#define M16C_PD10 0x003f6 /* Port P10 direction */ +#define M16C_PUR0 0x003fc /* Pull-up control 0 */ +#define M16C_PUR1 0x003fd /* Pull-up control 1 */ +#define M16C_PUR2 0x003fe /* Pull-up control 2 */ +#define M16C_PCR 0x003ff /* Port control */ + +#endif /* __ARCH_SH_SRC_M16C_CHIP_H */ \ No newline at end of file diff --git a/nuttx/arch/sh/src/m16c/m16c_head.S b/nuttx/arch/sh/src/m16c/m16c_head.S new file mode 100644 index 000000000..753f98c20 --- /dev/null +++ b/nuttx/arch/sh/src/m16c/m16c_head.S @@ -0,0 +1,393 @@ +/************************************************************************************ + * arch/sh/src/m16c/chip.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Macro Definitions + ************************************************************************************/ + +/* Zero a block of memory */ + + .macro m16c_bzero, start, end + mov.b #0x00, R0L + mov.w #(\start & 0x0ffff), A1 + mov.w #(\end & 0x0ffff), R3 + sub.w A1, R3 + sstr.b + .endm + +/* Copy a block of memory */ + + .macro m16c_memcpy, dest, src, end + mov.w #(\dest & 0x0ffff),A0 + mov.b #(\dest >> 16), R1H + mov.w #\src, A1 + mov.w #(\end & 0x0ffff), R3 + sub.w A1, R3 + smovf.b + .endm + +/* Special page vectors. This macro puts the jump address of + * functions defined as special page into the special page vector table. + * See example calls below and see the M16C Software Manual or NC30 + * manual for more information on special page vectors. + */ +#if 0 + .macro m16c_special, num + .org 0x0ffffe-(\num*2) + .globl __SPECIAL_\num + .word __SPECIAL_\num & 0x0ffff + .endm +#enif + +/************************************************************************************ + * Data + ************************************************************************************/ + +/* The near RAM memory map is as follows: + * + * 0x00400 - DATA Size: Determined by linker + * BSS Size: Determined by linker + * Idle stack Size: CONFIG_IDLETHREAD_STACKSIZE + * Interrupt stack Size: CONFIG_M16C_ISTACKSIZE + * Heap Size: Everything remaining + * 0x00bff - (end+1) + */ + + .data + .globl _g_stackbase + .type _g_stackbase, object +_g_stackbase: + .word _enbss + .size _g_heapbase, .-_g_heapbase + .size _g_istackbase, .-_g_istackbase + + .globl _g_istackbase + .type _g_istackbase, object +_g_istackbase: + .word _enbss+CONFIG_IDLETHREAD_STACKSIZE-4 + .size _g_istackbase, .-_g_istackbase + + + * The heap extends from _g_heapbase to the end of RAM. + */ + .globl _g_heapbase + .type _g_heapbase, object +_g_heapbase: + .word _enbss+CONFIG_IDLETHREAD_STACKSIZE+CONFIG_M16C_ISTACKSIZE + .size _g_heapbase, .-_g_heapbase + +/************************************************************************************ + * Interrupt Vectors + ************************************************************************************/ + +/* Variable vector section */ + + .section varvects /* Variable vector table */ + .globl _m16c_unexpected_isr + .globl _m16c_brk_isr + .long _m16c_brk_isr /* ffd00: BRK instruction */ + .long 0xffffffff /* ffd04 */ + .long 0xffffffff /* ffd08 */ + .long 0xffffffff /* ffd0c */ + .globl _m16c_int3_isr + .long _m16c_int3_isr /* ffd10: INT3 */ +#ifdef CONFIG_M16C_SWINTS + .globl _m16c_swint5_isr + .long _m16c_swint5_isr /* ffd14: S/W interrupt 5 */ + .globl _m16c_swint6_isr + .long _m16c_swint6_isr /* ffd18: S/W interrupt 6 */ + .globl _m16c_swint7_isr + .long _m16c_swint7_isr /* ffd1c: S/W interrupt 7 */ +#else + .long _m16c_unexpected_isr /* ffd14: Reserved */ + .long _m16c_unexpected_isr /* ffd18: Reserved */ + .long _m16c_unexpected_isr /* ffd1c: Reserved */ +#endif + .globl _m16c_int5_isr + .long _m16c_int5_isr /* ffd20: INT5 */ + .globl _m16c_int4_isr + .long _m16c_int4_isr /* ffd24: INT4 */ + .globl _m16c_uart2bcd_isr + .long _m16c_uart2bcd_isr /* ffd28: UART2 bus collision detection */ + .globl _m16c_dma0_isr + .long _m16c_dma0_isr /* ffd2c: DMA0 */ + .globl _m16c_dma1_isr + .long _m16c_dma1_isr /* ffd30: DMA1 */ + .globl _m16c_keyinp_isr + .long _m16c_keyinp_isr /* ffd34: Key input interrupt */ + .globl _m16c_adc_isr + .long _m16c_adc_isr /* ffd38: A-D */ + .globl _m16c_uart2xmitnack2_isr + .long _m16c_uart2xmitnack2_isr /* ffd3c UART2 transmit/NACK2 */ + .globl _m16c_uart2rcvack2_isr + .long _m16c_uart2rcvack2_isr /* ffd40: UART2 receive/ACK2 */ + .globl _m16c_uart0xmit_isr + .long _m16c_uart0xmit_isr /* ffd44: UART0 transmit */ + .globl _m16c_uart0rcv_isr + .long _m16c_uart0rcv_isr /* ffd48: UART0 receive */ + .globl _m16c_uart1xmit_isr + .long _m16c_uart1xmit_isr /* ffd4c: UART1 transmit */ + .globl _m16c_uart1rcv_isr + .long _m16c_uart1rcv_isr /* ffd50: UART1 receive */ + .globl _m16c_tmra0_isr + .long _m16c_tmra0_isr /* ffd54: Timer A0 */ + .globl _m16c_tmra1_isr + .long _m16c_tmra1_isr /* ffd58: Timer A1 */ + .globl _m16c_tmra2_isr + .long _m16c_tmra2_isr /* ffd5c: Timer A2 */ + .globl _m16c_tmra3_isr + .long _m16c_tmra3_isr /* ffd60: Timer A3 */ + .globl _m16c_tmra4_isr + .long _m16c_tmra4_isr /* ffd64: Timer A4 */ + .globl _m16c_tmrb0_isr + .long _m16c_tmrb0_isr /* ffd68: Timer B0 */ + .globl _m16c_tmrb1_isr + .long _m16c_tmrb1_isr /* ffd6c: Timer B1 */ + .globl _m16c_tmrb2_isr + .long _m16c_tmrb2_isr /* ffd70: Timer B2 */ + .globl _m16c_int0_isr + .long _m16c_int0_isr /* ffd74: INT0 */ + .globl _m16c_int1_isr + .long _m16c_int1_isr /* ffd78: INT1 */ +#ifdef CONFIG_M16C_SWINTS + .globl _m16c_swint31_isr + .long _m16c_swint31_isr /* ffd7c: S/W interrupt 31 */ + .globl _m16c_swint32_isr + .long _m16c_swint32_isr /* ffd80: S/W interrupt 32 */ + .globl _m16c_swint33_isr + .long _m16c_swint33_isr /* ffd84: S/W interrupt 33 */ + .globl _m16c_swint34_isr + .long _m16c_swint34_isr /* ffd88: S/W interrupt 34 */ + .globl _m16c_swint35_isr + .long _m16c_swint35_isr /* ffd8c: S/W interrupt 35 */ + .globl _m16c_swint36_isr + .long _m16c_swint36_isr /* ffd90: S/W interrupt 36 */ + .globl _m16c_swint37_isr + .long _m16c_swint37_isr /* ffd94: S/W interrupt 37 */ + .globl _m16c_swint38_isr + .long _m16c_swint38_isr /* ffd98: S/W interrupt 38 */ + .globl _m16c_swint39_isr + .long _m16c_swint39_isr /* ffd9c: S/W interrupt 39 */ + .globl _m16c_swint40_isr + .long _m16c_swint40_isr /* ffda0: S/W interrupt 40 */ + .globl _m16c_swint41_isr + .long _m16c_swint41_isr /* ffda4: S/W interrupt 41 */ + .globl _m16c_swint42_isr + .long _m16c_swint42_isr /* ffda8: S/W interrupt 42 */ + .globl _m16c_swint43_isr + .long _m16c_swint43_isr /* ffdac: S/W interrupt 43 */ + .globl _m16c_swint44_isr + .long _m16c_swint44_isr /* ffdb0: S/W interrupt 44 */ + .globl _m16c_swint45_isr + .long _m16c_swint45_isr /* ffdb4: S/W interrupt 45 */ + .globl _m16c_swint46_isr + .long _m16c_swint46_isr /* ffdb8: S/W interrupt 46 */ + .globl _m16c_swint47_isr + .long _m16c_swint47_isr /* ffdbc: S/W interrupt 47 */ + .globl _m16c_swint48_isr + .long _m16c_swint48_isr /* ffdc0: S/W interrupt 48 */ + .globl _m16c_swint49_isr + .long _m16c_swint49_isr /* ffdc4: S/W interrupt 49 */ + .globl _m16c_swint50_isr + .long _m16c_swint50_isr /* ffdc8: S/W interrupt 50 */ + .globl _m16c_swint51_isr + .long _m16c_swint51_isr /* ffdcc: S/W interrupt 51 */ + .globl _m16c_swint52_isr + .long _m16c_swint52_isr /* ffdd0: S/W interrupt 52 */ + .globl _m16c_swint53_isr + .long _m16c_swint53_isr /* ffdd4: S/W interrupt 53 */ + .globl _m16c_swint54_isr + .long _m16c_swint54_isr /* ffdd8: S/W interrupt 54 */ + .globl _m16c_swint55_isr + .long _m16c_swint55_isr /* ffddc: S/W interrupt 55 */ + .globl _m16c_swint56_isr + .long _m16c_swint56_isr /* ffde0: S/W interrupt 56 */ + .globl _m16c_swint57_isr + .long _m16c_swint57_isr /* ffde4: S/W interrupt 57 */ + .globl _m16c_swint58_isr + .long _m16c_swint58_isr /* ffde8: S/W interrupt 58 */ + .globl _m16c_swint59_isr + .long _m16c_swint59_isr /* ffdec: S/W interrupt 59 */ + .globl _m16c_swint60_isr + .long _m16c_swint60_isr /* ffdf0: S/W interrupt 60 */ + .globl _m16c_swint61_isr + .long _m16c_swint61_isr /* ffdf4: S/W interrupt 61 */ + .globl _m16c_swint62_isr + .long _m16c_swint62_isr /* ffdf8: S/W interrupt 62 */ + .globl _m16c_swint63_isr + .long _m16c_swint63_isr /* ffdfc: S/W interrupt 63 */ +#else + .long _m16c_unexpected_isr /* ffd7c: Reserved */ + .long _m16c_unexpected_isr /* ffd80: Not supported */ + .long _m16c_unexpected_isr /* ffd84: Not supported */ + .long _m16c_unexpected_isr /* ffd88: Not supported */ + .long _m16c_unexpected_isr /* ffd8c: Not supported */ + .long _m16c_unexpected_isr /* ffd90: Not supported */ + .long _m16c_unexpected_isr /* ffd94: Not supported */ + .long _m16c_unexpected_isr /* ffd98: Not supported */ + .long _m16c_unexpected_isr /* ffd9c: Not supported */ + .long _m16c_unexpected_isr /* ffda0: Not supported */ + .long _m16c_unexpected_isr /* ffda4: Not supported1 */ + .long _m16c_unexpected_isr /* ffda8: Not supported */ + .long _m16c_unexpected_isr /* ffdac: Not supported */ + .long _m16c_unexpected_isr /* ffdb0: Not supported */ + .long _m16c_unexpected_isr /* ffdb4: Not supported */ + .long _m16c_unexpected_isr /* ffdb8: Not supported */ + .long _m16c_unexpected_isr /* ffdbc: Not supported */ + .long _m16c_unexpected_isr /* ffdc0: Not supported */ + .long _m16c_unexpected_isr /* ffdc4: Not supported */ + .long _m16c_unexpected_isr /* ffdc8: Not supported */ + .long _m16c_unexpected_isr /* ffdcc: Not supported1 */ + .long _m16c_unexpected_isr /* ffdd0: Not supported */ + .long _m16c_unexpected_isr /* ffdd4: Not supported3 */ + .long _m16c_unexpected_isr /* ffdd8: Not supported */ + .long _m16c_unexpected_isr /* ffddc: Not supported */ + .long _m16c_unexpected_isr /* ffde0: Not supported */ + .long _m16c_unexpected_isr /* ffde4: Not supported7 */ + .long _m16c_unexpected_isr /* ffde8: Not supported */ +\ .long _m16c_unexpected_isr /* ffdec: Not supported */ + .long _m16c_unexpected_isr /* ffdf0: Not supported0 */ + .long _m16c_unexpected_isr /* ffdf4: Not supported */ + .long _m16c_unexpected_isr /* ffdf8: Not supported */ + .long _m16c_unexpected_isr /* ffdfc: Not supported */ +#endif + +/* Fixed vector section + * + * The fixed vector table begins at address ffe00. The firt portion + * of the fixed vector table is the special page table. This table + * is not currently used. + */ + .section specpg /* Special page table */ + + .section fixvects /* Fixed vector table */ + .globl _m16c_undefinst_irq + .long _m16c_undefinst_irq /* fffdc: Undefined instruction */ + .globl _m16c_overflow_irq + .long _m16c_overflow_irq /* fffe0: Overflow */ + .globl _m16c_brkinst_irq + .long _m16c_brkinst_irq /* fffe4: BRK instruction */ + .globl _m16c_addrmatch_irq + .long _m16c_addrmatch_irq /* fffe8: Address match */ +#ifdef CONFIG_M16C_DEBUGGER + .globl _m16c_sstep_irq + .long _m16c_sstep_irq /* fffec: Single step */ +#else + .long _m16c_unexpected_isr /* fffec: Not supported */ +#endif + .globl _m16c_wdog_irq + .long _m16c_wdog_irq /* ffff0: Watchdog timer */ +#ifdef CONFIG_M16C_DEBUGGER + .globl _m16c_dbc_irq + .long _m16c_dbc_irq /* ffff4: DBC */ +#else + .long _m16c_unexpected_isr /* ffff4: Not supported */ +#endif + .globl _m16c_nmi_irq + .long _m16c_nmi_irq /* ffff8: NMI */ + .long __start /* ffffc: Reset */ + +/************************************************************************************ + * Code + ************************************************************************************/ +/************************************************************************************ + * Name: _start + * + * Description: + * After reset, program execution starts here. + * + ************************************************************************************/ + + .text + .global __start + .type __start, #function +__start: + +/* Set the istack pointer */ + + ldc #_enbss, isp /* Set idle thread stack pointer to the end of BSS */ + +/* Set BCLK speed. At reset, the processor clock (BLCK) defaults to a divisor of 8. + * This sets clock to F1 (divide by 1) on XIN: BCLK = XIN frequency. + */ + + mov.b #0x01h, M16C_PRCR /* Unprotect CM0 to change clock setting */ + mov.b #0x08h, M16C_CM0 /* enable CM17 and CM16 to set BCLK to F1 + * CM17 & CM16 defaults to 0 after reset and + * so we only need to reset CM06 to 0 */ + mov.b #0x00,M16C_PRCR /* protect CM0 */ + +/* The two MS bits of the interrupt cause select register must be set to + * enable the use of INT4 and INT5 + */ + + mov.b #0xc0, M16C_IFSR /* Set b7 & b6 if application will use INT4 & INT5 */ + ldc #M16C_IRAM_BASE, sb /* Set sb register (to what?) */ + ldintb #_svarvect + +/* Clear .bss sections */ + + m16c_bzero _snbss, _enbss +#ifdef CONFIG_M16C_HAVEFARRAM + m16c_bzero _sfbss, _efbss +#endif + +/* Initialize .data sections */ + + m16c_memcpy _sndata, _enronly, _endata +#ifdef CONFIG_M16C_HAVEFARRAM + m16c_memcpy _sfdata, _efronly, _efdata +#endif + +/* Pass control to NuttX */ + + .glbl _os_start + jsr.a _os_start + +/* NuttX will not return, but just in case... */ + +.Lreturned: + jmp .Lreturned -- cgit v1.2.3