From b029fd50d5155c902bb4f4e0787891ca1d324cbd Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 5 Nov 2008 22:00:09 +0000 Subject: Adding struture for Hitachi SH-1 git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1132 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/sh/include/README.txt | 5 + nuttx/arch/sh/include/arch.h | 79 ++++++++++++ nuttx/arch/sh/include/irq.h | 229 +++++++++++++++++++++++++++++++++++ nuttx/arch/sh/include/limits.h | 75 ++++++++++++ nuttx/arch/sh/include/serial.h | 55 +++++++++ nuttx/arch/sh/include/sh1/README.txt | 3 + nuttx/arch/sh/include/sh1/irq.h | 120 ++++++++++++++++++ nuttx/arch/sh/include/types.h | 82 +++++++++++++ nuttx/arch/sh/include/watchdog.h | 59 +++++++++ nuttx/arch/sh/src/README.txt | 7 ++ nuttx/arch/sh/src/common/README.txt | 2 + nuttx/arch/sh/src/sh1/README.txt | 2 + 12 files changed, 718 insertions(+) create mode 100644 nuttx/arch/sh/include/README.txt create mode 100644 nuttx/arch/sh/include/arch.h create mode 100644 nuttx/arch/sh/include/irq.h create mode 100644 nuttx/arch/sh/include/limits.h create mode 100644 nuttx/arch/sh/include/serial.h create mode 100644 nuttx/arch/sh/include/sh1/README.txt create mode 100644 nuttx/arch/sh/include/sh1/irq.h create mode 100644 nuttx/arch/sh/include/types.h create mode 100644 nuttx/arch/sh/include/watchdog.h create mode 100644 nuttx/arch/sh/src/README.txt create mode 100644 nuttx/arch/sh/src/common/README.txt create mode 100644 nuttx/arch/sh/src/sh1/README.txt (limited to 'nuttx/arch/sh') diff --git a/nuttx/arch/sh/include/README.txt b/nuttx/arch/sh/include/README.txt new file mode 100644 index 000000000..c07708aec --- /dev/null +++ b/nuttx/arch/sh/include/README.txt @@ -0,0 +1,5 @@ +This directory contains header files common to all SH architectures. +Sub-directories within this directory contain header files unique to +specific SH chip architectures. At configuration time, additional directories +will be linked here: 'build' will be a link to the configs/*/include +directory; 'chip' will be a link to the SH chip sub-directory. diff --git a/nuttx/arch/sh/include/arch.h b/nuttx/arch/sh/include/arch.h new file mode 100644 index 000000000..81853b12e --- /dev/null +++ b/nuttx/arch/sh/include/arch.h @@ -0,0 +1,79 @@ +/**************************************************************************** + * arch/sh/include/arch.h + * + * Copyright (C) 2008 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, + * only indirectly through nuttx/arch.h + */ + +#ifndef __ARCH_SH_INCLUDE_ARCH_H +#define __ARCH_SH_INCLUDE_ARCH_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Inline functions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __ARCH_SH_INCLUDE_ARCH_H */ diff --git a/nuttx/arch/sh/include/irq.h b/nuttx/arch/sh/include/irq.h new file mode 100644 index 000000000..075e0317a --- /dev/null +++ b/nuttx/arch/sh/include/irq.h @@ -0,0 +1,229 @@ +/**************************************************************************** + * arch/sh/include/irq.h + * + * Copyright (C) 2008 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 Gregory Nutt 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, + * only indirectly through nuttx/irq.h + */ + +#ifndef __ARCH_SH_INCLUDE_IRQ_H +#define __ARCH_SH_INCLUDE_IRQ_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* IRQ Stack Frame Format: + * + * Context is always saved/restored in the same way: + * + * (1) stmia rx, {r0-r14} + * (2) then the PC and CPSR + * + * This results in the following set of indices that + * can be used to access individual registers in the + * xcp.regs array: + */ + +#define REG_R0 (0) +#define REG_R1 (1) +#define REG_R2 (2) +#define REG_R3 (3) +#define REG_R4 (4) +#define REG_R5 (5) +#define REG_R6 (6) +#define REG_R7 (7) +#define REG_R8 (8) +#define REG_R9 (9) +#define REG_R10 (10) +#define REG_R11 (11) +#define REG_R12 (12) +#define REG_R13 (13) +#define REG_R14 (14) +#define REG_R15 (15) +#define REG_CPSR (16) + +#define XCPTCONTEXT_REGS (17) +#define XCPTCONTEXT_SIZE (4 * XCPTCONTEXT_REGS) + +#define REG_A1 REG_R0 +#define REG_A2 REG_R1 +#define REG_A3 REG_R2 +#define REG_A4 REG_R3 +#define REG_V1 REG_R4 +#define REG_V2 REG_R5 +#define REG_V3 REG_R6 +#define REG_V4 REG_R7 +#define REG_V5 REG_R8 +#define REG_V6 REG_R9 +#define REG_V7 REG_R10 +#define REG_SB REG_R9 +#define REG_SL REG_R10 +#define REG_FP REG_R11 +#define REG_IP REG_R12 +#define REG_SP REG_R13 +#define REG_LR REG_R14 +#define REG_PC REG_R15 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This struct defines the way the registers are stored. We + * need to save: + * + * 1 CPSR + * 7 Static registers, v1-v7 (aka r4-r10) + * 1 Frame pointer, fp (aka r11) + * 1 Stack pointer, sp (aka r13) + * 1 Return address, lr (aka r14) + * --- + * 11 (XCPTCONTEXT_USER_REG) + * + * On interrupts, we also need to save: + * 4 Volatile registers, a1-a4 (aka r0-r3) + * 1 Scratch Register, ip (aka r12) + *--- + * 5 (XCPTCONTEXT_IRQ_REGS) + * + * For a total of 17 (XCPTCONTEXT_REGS) + */ + +#ifndef __ASSEMBLY__ +struct xcptcontext +{ + /* The following function pointer is non-zero if there + * are pending signals to be processed. + */ + +#ifndef CONFIG_DISABLE_SIGNALS + void *sigdeliver; /* Actual type is sig_deliver_t */ +#endif + + /* These are saved copies of LR and CPSR used during + * signal processing. + */ + + uint32 saved_pc; + uint32 saved_cpsr; + + /* Register save area */ + + uint32 regs[XCPTCONTEXT_REGS]; +}; +#endif + +/**************************************************************************** + * Inline functions + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/* Save the current interrupt enable state & disable IRQs */ + +static inline irqstate_t irqsave(void) +{ + unsigned int flags; + unsigned int temp; + __asm__ __volatile__ + ( + "\tmrs %0, cpsr\n" + "\torr %1, %0, #128\n" + "\tmsr cpsr_c, %1" + : "=r" (flags), "=r" (temp) + : + : "memory"); + return flags; +} + +/* Restore saved IRQ & FIQ state */ + +static inline void irqrestore(irqstate_t flags) +{ + __asm__ __volatile__ + ( + "msr cpsr_c, %0" + : + : "r" (flags) + : "memory"); +} + +static inline void system_call(swint_t func, int parm1, + int parm2, int parm3) +{ + __asm__ __volatile__ + ( + "mov\tr0,%0\n\t" + "mov\tr1,%1\n\t" + "mov\tr2,%2\n\t" + "mov\tr3,%3\n\t" + "swi\t0x900001\n\t" + : + : "r" ((long)(func)), "r" ((long)(parm1)), + "r" ((long)(parm2)), "r" ((long)(parm3)) + : "r0", "r1", "r2", "r3", "lr"); +} +#endif + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_SH_INCLUDE_IRQ_H */ + diff --git a/nuttx/arch/sh/include/limits.h b/nuttx/arch/sh/include/limits.h new file mode 100644 index 000000000..16e63f551 --- /dev/null +++ b/nuttx/arch/sh/include/limits.h @@ -0,0 +1,75 @@ +/**************************************************************************** + * arch/sh/include/limits.h + * + * Copyright (C) 2008 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_INCLUDE_LIMITS_H +#define __ARCH_SH_INCLUDE_LIMITS_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define CHAR_BIT 8 +#define SCHAR_MIN 0x80 +#define SCHAR_MAX 0x7f +#define UCHAR_MAX 0xff + +/* These could be different on machines where char is unsigned */ + +#define CHAR_MIN SCHAR_MIN +#define CHAR_MAX SCHAR_MAX + +#define SHRT_MIN 0x8000 +#define SHRT_MAX 0x7fff +#define USHRT_MAX 0xffff + +#define INT_MIN 0x80000000 +#define INT_MAX 0x7fffffff +#define UINT_MAX 0xffffffff + +/* These change on 32-bit and 64-bit platforms */ + +#define LONG_MAX 0x80000000 +#define LONG_MIN 0x7fffffff +#define ULONG_MAX 0xffffffff + +#define LLONG_MAX 0x8000000000000000 +#define LLONG_MIN 0x7fffffffffffffff +#define ULLONG_MAX 0xffffffffffffffff + +#endif /* __ARCH_SH_INCLUDE_LIMITS_H */ diff --git a/nuttx/arch/sh/include/serial.h b/nuttx/arch/sh/include/serial.h new file mode 100644 index 000000000..2790b0871 --- /dev/null +++ b/nuttx/arch/sh/include/serial.h @@ -0,0 +1,55 @@ +/**************************************************************************** + * arch/sh/include/serial.h + * + * Copyright (C) 2008 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_INCLUDE_SERIAL_H +#define __ARCH_SH_INCLUDE_SERIAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* __ARCH_SH_INCLUDE_SERIAL_H */ diff --git a/nuttx/arch/sh/include/sh1/README.txt b/nuttx/arch/sh/include/sh1/README.txt new file mode 100644 index 000000000..dabd6e83a --- /dev/null +++ b/nuttx/arch/sh/include/sh1/README.txt @@ -0,0 +1,3 @@ +This directory contains header files common to all SH architectures. +Sub-directories within this directory contain header files unique to +specific SH architectures. diff --git a/nuttx/arch/sh/include/sh1/irq.h b/nuttx/arch/sh/include/sh1/irq.h new file mode 100644 index 000000000..795289c6f --- /dev/null +++ b/nuttx/arch/sh/include/sh1/irq.h @@ -0,0 +1,120 @@ +/************************************************************************************ + * arch/sh/include/sh1/irq.h + * + * Copyright (C) 2008 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. + * + ************************************************************************************/ + +/* This file should never be included directed but, rather, + * only indirectly through nuttx/irq.h + */ + +#ifndef __ARCH_SH_INCLUDE_SH1_IRQ_H +#define __ARCH_SH_INCLUDE_SH1_IRQ_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* IRQ channels */ + +#define STR71X_IRQ_T0TIMI (0) +#define STR71X_IRQ_FLASH (1) +#define STR71X_IRQ_RCCU (2) +#define STR71X_IRQ_RTC (3) +#define STR71X_IRQ_WDG (4) +#define STR71X_IRQ_XTI (5) +#define STR71X_IRQ_USBHP (6) +#define STR71X_IRQ_I2C0ITERR (7) +#define STR71X_IRQ_I2C1ITERR (8) +#define STR71X_IRQ_UART0 (9) +#define STR71X_IRQ_UART1 (10) +#define STR71X_IRQ_UART2 (11) +#define STR71X_IRQ_UART3 (12) +#define STR71X_IRQ_SPI0 (13) +#define STR71X_IRQ_SPI1 (14) +#define STR71X_IRQ_I2C0 (15) +#define STR71X_IRQ_I2C1 (16) +#define STR71X_IRQ_CAN (17) +#define STR71X_IRQ_ADC (18) +#define STR71X_IRQ_T1TIMI (19) +#define STR71X_IRQ_T2TIMI (20) +#define STR71X_IRQ_T3TIMI (21) +#define STR71X_IRQ_HDLC (25) +#define STR71X_IRQ_USBLP (26) +#define STR71X_IRQ_T0TOI (29) +#define STR71X_IRQ_T0OC1 (30) +#define STR71X_IRQ_T0OC2 (31) + +#define STR71X_IRQ_SYSTIMER STR71X_IRQ_T0TIMI +#define NR_IRQS 32 + +/* FIQ channels */ + +#define STR71X_FIQ_T0TIMI (0X00000001) +#define STR71X_FIQ_WDG (0X00000002) +#define STR71X_FIQ_WDGT0TIMIS (0X00000003) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_SH_INCLUDE_SH1_IRQ_H */ + diff --git a/nuttx/arch/sh/include/types.h b/nuttx/arch/sh/include/types.h new file mode 100644 index 000000000..531632620 --- /dev/null +++ b/nuttx/arch/sh/include/types.h @@ -0,0 +1,82 @@ +/**************************************************************************** + * arch/sh/include/types.h + * + * Copyright (C) 2008 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, + * only indirectly through sys/types.h + */ + +#ifndef __ARCH_SH_INCLUDE_TYPES_H +#define __ARCH_SH_INCLUDE_TYPES_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Type Declarations + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/* These are the sizes of the standard GNU types */ + +typedef char sbyte; +typedef unsigned char ubyte; +typedef unsigned char uint8; +typedef unsigned char boolean; +typedef short sint16; +typedef unsigned short uint16; +typedef int sint32; +typedef unsigned int uint32; +typedef long long sint64; +typedef unsigned long long uint64; + +/* This is the size of the interrupt state save returned by + * irqsave() + */ + +typedef unsigned int irqstate_t; + +#endif /* __ASSEMBLY__ */ + +/**************************************************************************** + * Global Function Prototypes + ****************************************************************************/ + +#endif /* __ARCH_SH_INCLUDE_TYPES_H */ diff --git a/nuttx/arch/sh/include/watchdog.h b/nuttx/arch/sh/include/watchdog.h new file mode 100644 index 000000000..2b70dfc88 --- /dev/null +++ b/nuttx/arch/sh/include/watchdog.h @@ -0,0 +1,59 @@ +/**************************************************************************** + * arch/sh/include/watchdog.h + * + * Copyright (C) 2008 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_INCLUDE_WATCHDOG_H +#define __ARCH_SH_INCLUDE_WATCHDOG_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* __ARCH_SH_INCLUDE_WATCHDOG_H */ diff --git a/nuttx/arch/sh/src/README.txt b/nuttx/arch/sh/src/README.txt new file mode 100644 index 000000000..3cbd17c0f --- /dev/null +++ b/nuttx/arch/sh/src/README.txt @@ -0,0 +1,7 @@ +This directory provides a build area for all SH architectures. +The 'common' subdirectory contains source files shared by all SH +architectures; Source files unique to a specific SH chip +architecture are contained in a subdirectory named after the chip. +At configuration time, additional directories will be linked here: +'build' will be a link to the configs/*/src directory; 'chip' will +be a link to the SH chip sub-directory. diff --git a/nuttx/arch/sh/src/common/README.txt b/nuttx/arch/sh/src/common/README.txt new file mode 100644 index 000000000..cd2bc8b53 --- /dev/null +++ b/nuttx/arch/sh/src/common/README.txt @@ -0,0 +1,2 @@ +This directory contains source files that are common to all +SH architectures. \ No newline at end of file diff --git a/nuttx/arch/sh/src/sh1/README.txt b/nuttx/arch/sh/src/sh1/README.txt new file mode 100644 index 000000000..d65395656 --- /dev/null +++ b/nuttx/arch/sh/src/sh1/README.txt @@ -0,0 +1,2 @@ +This directory contains source files that are unique to the SH-1 +chip architecture. -- cgit v1.2.3