summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-08 16:22:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-06-08 16:22:50 +0000
commit583f057b1912513fce544714949e29fbe8bdf253 (patch)
tree6fa6c2633c96ae9f0267ac9a756de81634ea1500 /nuttx/arch
parentb2c3a559c7701728526026fcd64e85d9004715f2 (diff)
downloadpx4-nuttx-583f057b1912513fce544714949e29fbe8bdf253.tar.gz
px4-nuttx-583f057b1912513fce544714949e29fbe8bdf253.tar.bz2
px4-nuttx-583f057b1912513fce544714949e29fbe8bdf253.zip
Add basic context switching logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3682 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/avr/include/at90usb/irq.h2
-rw-r--r--nuttx/arch/avr/include/avr/irq.h44
-rw-r--r--nuttx/arch/avr/include/avr/types.h14
-rw-r--r--nuttx/arch/avr/src/at90usb/Make.defs12
-rwxr-xr-xnuttx/arch/avr/src/at90usb/at90usb_exceptions.S125
-rwxr-xr-xnuttx/arch/avr/src/at90usb/at90usb_head.S4
-rw-r--r--nuttx/arch/avr/src/atmega/Make.defs12
-rwxr-xr-xnuttx/arch/avr/src/atmega/atmega_exceptions.S118
-rwxr-xr-xnuttx/arch/avr/src/atmega/atmega_head.S2
-rwxr-xr-xnuttx/arch/avr/src/avr/excptmacros.h524
-rw-r--r--nuttx/arch/avr/src/avr/up_copystate.c86
-rwxr-xr-xnuttx/arch/avr/src/avr/up_switchcontext.S134
-rw-r--r--nuttx/arch/avr/src/avr32/up_copystate.c1
-rwxr-xr-xnuttx/arch/avr/src/avr32/up_exceptions.S2
14 files changed, 1050 insertions, 30 deletions
diff --git a/nuttx/arch/avr/include/at90usb/irq.h b/nuttx/arch/avr/include/at90usb/irq.h
index c2f9db4e6..8e6412125 100644
--- a/nuttx/arch/avr/include/at90usb/irq.h
+++ b/nuttx/arch/avr/include/at90usb/irq.h
@@ -63,7 +63,7 @@
#define AT90USB_IRQ_INT5 5 /* 0x000c External Interrupt Request 5 */
#define AT90USB_IRQ_INT6 6 /* 0x000e External Interrupt Request 6 */
#define AT90USB_IRQ_INT7 7 /* 0x0010 External Interrupt Request 7 */
-#define AT90USB_IRQ_PCINT0 8 /* 0x0012 PCINT0 Pin Change Interrupt Request 0 */
+#define AT90USB_IRQ_PCINT0 8 /* 0x0012 Pin Change Interrupt Request 0 */
#define AT90USB_IRQ_USBGEN 9 /* 0x0014 USB General USB General Interrupt request */
#define AT90USB_IRQ_USBEP 10 /* 0x0016 USB Endpoint/Pipe USB ENdpoint/Pipe Interrupt request */
#define AT90USB_IRQ_WDT 11 /* 0x0018 Watchdog Time-out Interrupt */
diff --git a/nuttx/arch/avr/include/avr/irq.h b/nuttx/arch/avr/include/avr/irq.h
index 07b875a0a..b387be671 100644
--- a/nuttx/arch/avr/include/avr/irq.h
+++ b/nuttx/arch/avr/include/avr/irq.h
@@ -52,12 +52,46 @@
****************************************************************************/
/* Register state save array indices */
-
-#define REG_Rx 0 /* Just a placeholder */
-/* Size of the register state save array (in bytes?) */
-
-#define XCPTCONTEXT_REGS 1
+#define REG_SPH 0 /* Stack pointer on exception entry */
+#define REG_SPL 1
+#define REG_R27 2 /* r26-r27 */
+#define REG_R26 3
+#define REG_R31 4 /* r18-r31 */
+#define REG_R30 5
+#define REG_R29 6
+#define REG_R28 7
+#define REG_R25 8 /* r25 */
+#define REG_R23 9 /* r2-r23 */
+#define REG_R22 10
+#define REG_R21 11
+#define REG_R20 12
+#define REG_R19 13
+#define REG_R18 14
+#define REG_R17 15
+#define REG_R16 16
+#define REG_R15 17
+#define REG_R14 18
+#define REG_R13 19
+#define REG_R12 20
+#define REG_R11 21
+#define REG_R10 22
+#define REG_R9 23
+#define REG_R8 24
+#define REG_R7 25
+#define REG_R6 26
+#define REG_R5 27
+#define REG_R4 28
+#define REG_R3 29
+#define REG_R2 30
+#define REG_R1 31 /* r1 - the "zero" register */
+#define REG_SREG 32 /* Status register */
+#define REG_R0 33 /* r0 */
+#define REG_R24 34 /* r24 */
+
+/* Size of the register state save array (in bytes) */
+
+#define XCPTCONTEXT_REGS 35
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/avr/include/avr/types.h b/nuttx/arch/avr/include/avr/types.h
index 2e30414c4..0ff769576 100644
--- a/nuttx/arch/avr/include/avr/types.h
+++ b/nuttx/arch/avr/include/avr/types.h
@@ -63,20 +63,20 @@
* files
*/
-typedef signed char _int8_t;
+typedef signed char _int8_t; /* char is 8-bits */
typedef unsigned char _uint8_t;
-typedef signed short _int16_t;
-typedef unsigned short _uint16_t;
+typedef signed int _int16_t; /* int is 16-bits */
+typedef unsigned int _uint16_t;
-typedef signed int _int32_t;
-typedef unsigned int _uint32_t;
+typedef signed long _int32_t; /* long is 32-bits */
+typedef unsigned long _uint32_t;
-typedef signed long long _int64_t;
+typedef signed long long _int64_t; /* long long is 64-bits */
typedef unsigned long long _uint64_t;
#define __INT64_DEFINED
-/* A pointer is 4 bytes */
+/* A pointer is 2 bytes */
typedef signed int _intptr_t;
typedef unsigned int _uintptr_t;
diff --git a/nuttx/arch/avr/src/at90usb/Make.defs b/nuttx/arch/avr/src/at90usb/Make.defs
index bc91ceb66..a206f4f6f 100644
--- a/nuttx/arch/avr/src/at90usb/Make.defs
+++ b/nuttx/arch/avr/src/at90usb/Make.defs
@@ -39,15 +39,15 @@ HEAD_ASRC = at90usb_head.S
# Common AVR files
-CMN_ASRCS =
-CMN_CSRCS = up_allocateheap.c up_createstack.c up_exit.c up_idle.c \
- up_initialize.c up_interruptcontext.c up_lowputs.c up_mdelay.c \
- up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c up_puts.c \
- up_releasestack.c up_udelay.c up_usestack.c
+CMN_ASRCS = up_switchcontext.S
+CMN_CSRCS = up_allocateheap.c up_copystate.c up_createstack.c up_exit.c \
+ up_idle.c up_initialize.c up_interruptcontext.c up_lowputs.c \
+ up_mdelay.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
+ up_puts.c up_releasestack.c up_udelay.c up_usestack.c
# Required aT90USB files
-CHIP_ASRCS =
+CHIP_ASRCS = at90usb_exceptions.S
CHIP_CSRCS =
# Configuration-dependent aT90USB files
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S b/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S
new file mode 100755
index 000000000..748fd5efc
--- /dev/null
+++ b/nuttx/arch/avr/src/at90usb/at90usb_exceptions.S
@@ -0,0 +1,125 @@
+/********************************************************************************************
+ * arch/avr/src/at90usb/at90usb_exceptions.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+
+#include <arch/irq.h>
+
+#include "excptmacros.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * External Symbols
+ ********************************************************************************************/
+
+ .file "at90usb_exceptions.S"
+ .global up_doirq
+
+/********************************************************************************************
+ * Macros
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Exception Vector Handlers
+ ********************************************************************************************/
+
+ .section .handlers, "ax", @progbits
+
+ HANDLER at90usb_int0, ATMEGA_IRQ_INT0, excpt_common /* External interrupt request 0 */
+ HANDLER at90usb_int1, ATMEGA_IRQ_INT1, excpt_common /* External interrupt request 1 */
+ HANDLER at90usb_int2, ATMEGA_IRQ_INT2, excpt_common /* External interrupt request 2 */
+ HANDLER at90usb_int3, ATMEGA_IRQ_INT3, excpt_common /* External interrupt request 3 */
+ HANDLER at90usb_int4, ATMEGA_IRQ_INT4, excpt_common /* External interrupt request 4 */
+ HANDLER at90usb_int5, ATMEGA_IRQ_INT5, excpt_common /* External interrupt request 5 */
+ HANDLER at90usb_int6, ATMEGA_IRQ_INT6, excpt_common /* External interrupt request 6 */
+ HANDLER at90usb_int7, ATMEGA_IRQ_INT7, excpt_common /* External interrupt request 7 */
+ HANDLER at90usb_pcint0, AT90USB_IRQ_PCINT0, excpt_common /* Pin Change Interrupt Request 0 */
+ HANDLER at90usb_usbgen, AT90USB_IRQ_USBGEN, excpt_common /* USB General USB General Interrupt request */
+ HANDLER at90usb_usbep, AT90USB_IRQ_USBEP, excpt_common /* USB Endpoint/Pipe USB ENdpoint/Pipe Interrupt request */
+ HANDLER at90usb_wdt, AT90USB_IRQ_WDT, excpt_common /* Watchdog Time-out Interrupt */
+ HANDLER at90usb_t2compa, AT90USB_IRQ_T2COMPA, excpt_common /* TIMER2 COMPA Timer/Counter2 Compare Match A */
+ HANDLER at90usb_t2compb, AT90USB_IRQ_T2COMPB, excpt_common /* TIMER2 COMPA Timer/Counter2 Compare Match B */
+ HANDLER at90usb_t2ovf, ATMEGA_IRQ_T2OVF, excpt_common /* TIMER2 OVF timer/counter2 overflow */
+ HANDLER at90usb_t1capt, ATMEGA_IRQ_T1CAPT, excpt_common /* TIMER1 CAPT timer/counter1 capture event */
+ HANDLER at90usb_t1compa, ATMEGA_IRQ_T1COMPA, excpt_common /* TIMER1 COMPA timer/counter1 compare match A */
+ HANDLER at90usb_t1compb, ATMEGA_IRQ_T1COMPB, excpt_common /* TIMER1 COMPB timer/counter1 compare match B */
+ HANDLER at90usb_t1compc, ATMEGA_IRQ_T1COMPC, excpt_common /* TIMER1 COMPC timer/counter1 compare match C */
+ HANDLER at90usb_t1ovf, ATMEGA_IRQ_T1OVF, excpt_common /* TIMER1 OVF timer/counter1 overflow */
+ HANDLER at90usb_t0compa, AT90USB_IRQ_T0COMPA, excpt_common /* TIMER0 COMPA Timer/Counter0 Compare Match A */
+ HANDLER at90usb_t0compb, AT90USB_IRQ_T0COMPB, excpt_common /* TIMER0 COMPB Timer/Counter0 Compare Match B */
+ HANDLER at90usb_t0ovf, ATMEGA_IRQ_T0OVF, excpt_common /* TIMER0 OVF timer/counter0 overflow */
+ HANDLER at90usb_spi, ATMEGA_IRQ_SPI, excpt_common /* STC SPI serial transfer complete */
+ HANDLER at90usb_u1rx, ATMEGA_IRQ_U1RX, excpt_common /* USART1 RX complete */
+ HANDLER at90usb_u1dre, ATMEGA_IRQ_U1DRE, excpt_common /* USART1 data register empty */
+ HANDLER at90usb_u1tx, ATMEGA_IRQ_U1TX, excpt_common /* USART1 TX complete */
+ HANDLER at90usb_anacomp, ATMEGA_IRQ_ANACOMP, excpt_common /* ANALOG COMP analog comparator */
+ HANDLER at90usb_adc, ATMEGA_IRQ_ADC, excpt_common /* ADC conversion complete */
+ HANDLER at90usb_ee, ATMEGA_IRQ_EE, excpt_common /* EEPROM ready */
+ HANDLER at90usb_t3capt, ATMEGA_IRQ_T3CAPT, excpt_common /* TIMER3 CAPT timer/counter3 capture event */
+ HANDLER at90usb_t3compa, ATMEGA_IRQ_T3COMPA, excpt_common /* TIMER3 COMPA timer/counter3 compare match a */
+ HANDLER at90usb_t3compb, ATMEGA_IRQ_T3COMPB, excpt_common /* TIMER3 COMPB timer/counter3 compare match b */
+ HANDLER at90usb_t3compc, ATMEGA_IRQ_T3COMPC, excpt_common /* TIMER3 COMPC timer/counter3 compare match c */
+ HANDLER at90usb_t3ovf, ATMEGA_IRQ_T3OVF, excpt_common /* TIMER3 OVF timer/counter3 overflow */
+ HANDLER at90usb_twi, ATMEGA_IRQ_TWI, excpt_common /* TWI two-wire serial interface */
+ HANDLER at90usb_spmrdy, ATMEGA_IRQ_SPMRDY, excpt_common /* Store program memory ready */
+
+/* Common exception handling logic. */
+
+excpt_common:
+#warning "Missing Logic"
+
+/****************************************************************************************************
+ * Name: up_interruptstack
+ ****************************************************************************************************/
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 0
+ .bss
+ .align 4
+ .globl up_interruptstack
+ .type up_interruptstack, object
+up_interruptstack:
+ .skip CONFIG_ARCH_INTERRUPTSTACK
+.Lintstackbase:
+ .size up_interruptstack, .-up_interruptstack
+#endif
+ .end
+
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_head.S b/nuttx/arch/avr/src/at90usb/at90usb_head.S
index 7a1d71e9f..16d4abcc1 100755
--- a/nuttx/arch/avr/src/at90usb/at90usb_head.S
+++ b/nuttx/arch/avr/src/at90usb/at90usb_head.S
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#define __AVR_ATmega128__
+
#include <avr/io.h>
#include <avr/sfr_defs.h>
@@ -83,7 +83,7 @@
.global at90usb_int5 /* External interrupt request 5 */
.global at90usb_int6 /* External interrupt request 6 */
.global at90usb_int7 /* External interrupt request 7 */
- .global at90usb_pcint0 /* PCINT0 Pin Change Interrupt Request 0 */
+ .global at90usb_pcint0 /* Pin Change Interrupt Request 0 */
.global at90usb_usbgen /* USB General USB General Interrupt request */
.global at90usb_usbep /* USB Endpoint/Pipe USB ENdpoint/Pipe Interrupt request */
.global at90usb_wdt /* Watchdog Time-out Interrupt */
diff --git a/nuttx/arch/avr/src/atmega/Make.defs b/nuttx/arch/avr/src/atmega/Make.defs
index fd01dfdb5..3699543dd 100644
--- a/nuttx/arch/avr/src/atmega/Make.defs
+++ b/nuttx/arch/avr/src/atmega/Make.defs
@@ -39,15 +39,15 @@ HEAD_ASRC = atmega_head.S
# Common AVR files
-CMN_ASRCS =
-CMN_CSRCS = up_allocateheap.c up_createstack.c up_exit.c up_idle.c \
- up_initialize.c up_interruptcontext.c up_lowputs.c up_mdelay.c \
- up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c up_puts.c \
- up_releasestack.c up_udelay.c up_usestack.c
+CMN_ASRCS = up_switchcontext.S
+CMN_CSRCS = up_allocateheap.c up_copystate.c up_createstack.c up_exit.c \
+ up_idle.c up_initialize.c up_interruptcontext.c up_lowputs.c \
+ up_mdelay.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
+ up_puts.c up_releasestack.c up_udelay.c up_usestack.c
# Required ATMEGA files
-CHIP_ASRCS =
+CHIP_ASRCS = atmega_exceptions.S
CHIP_CSRCS =
# Configuration-dependent ATMEGA files
diff --git a/nuttx/arch/avr/src/atmega/atmega_exceptions.S b/nuttx/arch/avr/src/atmega/atmega_exceptions.S
new file mode 100755
index 000000000..522eddbed
--- /dev/null
+++ b/nuttx/arch/avr/src/atmega/atmega_exceptions.S
@@ -0,0 +1,118 @@
+/********************************************************************************************
+ * arch/avr/src/atmega/atmega_exceptions.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+
+#include <arch/irq.h>
+
+#include "excptmacros.h"
+
+/********************************************************************************************
+ * External Symbols
+ ********************************************************************************************/
+
+ .file "atmega_exceptions.S"
+ .global up_doirq
+
+/********************************************************************************************
+ * Macros
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Exception Vector Handlers
+ ********************************************************************************************/
+
+ .section .handlers, "ax", @progbits
+
+ HANDLER atmega_int0, ATMEGA_IRQ_INT0, excpt_common /* External interrupt request 0 */
+ HANDLER atmega_int1, ATMEGA_IRQ_INT1, excpt_common /* External interrupt request 1 */
+ HANDLER atmega_int2, ATMEGA_IRQ_INT2, excpt_common /* External interrupt request 2 */
+ HANDLER atmega_int3, ATMEGA_IRQ_INT3, excpt_common /* External interrupt request 3 */
+ HANDLER atmega_int4, ATMEGA_IRQ_INT4, excpt_common /* External interrupt request 4 */
+ HANDLER atmega_int5, ATMEGA_IRQ_INT5, excpt_common /* External interrupt request 5 */
+ HANDLER atmega_int6, ATMEGA_IRQ_INT6, excpt_common /* External interrupt request 6 */
+ HANDLER atmega_int7, ATMEGA_IRQ_INT7, excpt_common /* External interrupt request 7 */
+ HANDLER atmega_t2comp, ATMEGA_IRQ_T2COMP, excpt_common /* TIMER2 COMP timer/counter2 compare match */
+ HANDLER atmega_t2ovf, ATMEGA_IRQ_T2OVF, excpt_common /* TIMER2 OVF timer/counter2 overflow */
+ HANDLER atmega_t1capt, ATMEGA_IRQ_T1CAPT, excpt_common /* TIMER1 CAPT timer/counter1 capture event */
+ HANDLER atmega_t1compa, ATMEGA_IRQ_T1COMPA, excpt_common /* TIMER1 COMPA timer/counter1 compare match a */
+ HANDLER atmega_t1compb, ATMEGA_IRQ_T1COMPB, excpt_common /* TIMER1 COMPB timer/counter1 compare match b */
+ HANDLER atmega_t1ovf, ATMEGA_IRQ_T1OVF, excpt_common /* TIMER1 OVF timer/counter1 overflow */
+ HANDLER atmega_t0comp, ATMEGA_IRQ_T0COMP, excpt_common /* TIMER0 COMP timer/counter0 compare match */
+ HANDLER atmega_t0ovf, ATMEGA_IRQ_T0OVF, excpt_common /* TIMER0 OVF timer/counter0 overflow */
+ HANDLER atmega_spi, ATMEGA_IRQ_SPI, excpt_common /* STC SPI serial transfer complete */
+ HANDLER atmega_u0rx, ATMEGA_IRQ_U0RX, excpt_common /* USART0 RX complete */
+ HANDLER atmega_u0dre, ATMEGA_IRQ_U0DRE, excpt_common /* USART0 data register empty */
+ HANDLER atmega_u0tx, ATMEGA_IRQ_U0TX, excpt_common /* USART0 TX complete */
+ HANDLER atmega_adc, ATMEGA_IRQ_ADC, excpt_common /* ADC conversion complete */
+ HANDLER atmega_ee, ATMEGA_IRQ_EE, excpt_common /* EEPROM ready */
+ HANDLER atmega_anacomp, ATMEGA_IRQ_ANACOMP, excpt_common /* ANALOG COMP analog comparator */
+ HANDLER atmega_t1compc, ATMEGA_IRQ_T1COMPC, excpt_common /* TIMER1 COMPC timer/countre1 compare match c */
+ HANDLER atmega_t3capt, ATMEGA_IRQ_T3CAPT, excpt_common /* TIMER3 CAPT timer/counter3 capture event */
+ HANDLER atmega_t3compa, ATMEGA_IRQ_T3COMPA, excpt_common /* TIMER3 COMPA timer/counter3 compare match a */
+ HANDLER atmega_t3compb, ATMEGA_IRQ_T3COMPB, excpt_common /* TIMER3 COMPB timer/counter3 compare match b */
+ HANDLER atmega_t3compc, ATMEGA_IRQ_T3COMPC, excpt_common /* TIMER3 COMPC timer/counter3 compare match c */
+ HANDLER atmega_t3ovf, ATMEGA_IRQ_T3OVF, excpt_common /* TIMER3 OVF timer/counter3 overflow */
+ HANDLER atmega_u1rx, ATMEGA_IRQ_U1RX, excpt_common /* USART1 RX complete */
+ HANDLER atmega_u1dre, ATMEGA_IRQ_U1DRE, excpt_common /* USART1 data register empty */
+ HANDLER atmega_u1tx, ATMEGA_IRQ_U1TX, excpt_common /* USART1 TX complete */
+ HANDLER atmega_twi, ATMEGA_IRQ_TWI, excpt_common /* TWI two-wire serial interface */
+ HANDLER atmega_spmrdy, ATMEGA_IRQ_SPMRDY, excpt_common /* Store program memory ready */
+
+/* Common exception handling logic. */
+
+excpt_common:
+#warning "Missing Logic"
+
+/****************************************************************************************************
+ * Name: up_interruptstack
+ ****************************************************************************************************/
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 0
+ .bss
+ .align 4
+ .globl up_interruptstack
+ .type up_interruptstack, object
+up_interruptstack:
+ .skip CONFIG_ARCH_INTERRUPTSTACK
+.Lintstackbase:
+ .size up_interruptstack, .-up_interruptstack
+#endif
+ .end
+
diff --git a/nuttx/arch/avr/src/atmega/atmega_head.S b/nuttx/arch/avr/src/atmega/atmega_head.S
index cd3c194dc..aff46a39e 100755
--- a/nuttx/arch/avr/src/atmega/atmega_head.S
+++ b/nuttx/arch/avr/src/atmega/atmega_head.S
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#define __AVR_ATmega128__
+
#include <avr/io.h>
#include <avr/sfr_defs.h>
diff --git a/nuttx/arch/avr/src/avr/excptmacros.h b/nuttx/arch/avr/src/avr/excptmacros.h
new file mode 100755
index 000000000..b4408f288
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/excptmacros.h
@@ -0,0 +1,524 @@
+/********************************************************************************************
+ * arch/avr/src/avr/excptmacros.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_AVR_SRC_AVR_EXCPTMACROS_H
+#define __ARCH_AVR_SRC_AVR_EXCPTMACROS_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifdef __ASSEMBLY__
+
+#include <arch/irq.h>
+
+#include <avr/io.h>
+#include <avr/sfr_defs.h>
+
+/********************************************************************************************
+ * Pre-Processor Definitions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+#ifndef __SREG__
+# define __SREG__ 0x3f
+#endif
+
+#ifndef __SP_H__
+# define __SP_H__ 0x3e
+#endif
+
+#ifndef __SP_L__
+# define __SP_L__ 0x3d
+#endif
+
+#ifndef __tmp_reg__
+# define __tmp_reg__ r0
+#endif
+
+#ifndef __zero_reg__
+# define __zero_reg__ r1
+#endif
+
+/********************************************************************************************
+ * Global Symbols
+ ********************************************************************************************/
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ .global g_intstackbase
+ .global g_nestlevel
+#endif
+
+/********************************************************************************************
+ * Assembly Language Macros
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * General Exception Handling Example:
+ *
+ * HANDLER IRQ_X, my_exception
+ * ...
+ * my_exception:
+ * EXCPT_PROLOGUE - Save registers on stack, enable nested interrupts
+ * in r22, __SP_L__ - Pass register save structure as the parameter 2
+ * in r23, __SP_H__ - (Careful, push post-decrements)
+ * USE_INTSTACK rx, ry, rz - Switch to the interrupt stack
+ * call handler - Handle the exception IN=old regs OUT=new regs
+ * RESTORE_STACK rx, ry - Undo the operations of USE_STACK
+ *
+ * EXCPT_EPILOGUE - Return to the context returned by handler()
+ *
+ ********************************************************************************************/
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/********************************************************************************************
+ * Name: HANDLER
+ *
+ * Description:
+ * This macro provides the exception entry logic. It simply saves one register on the
+ * stack (r24) and passes the IRQ number to to common logic (see EXCPT_PROLOGUE).
+ *
+ * On Entry:
+ * sp - Points to the top of the stack
+ * Only the stack is available for storage
+ *
+ * At completion:
+ * Stack pointer is incremented by one, the saved r24 is on the stack, r24 now contains the
+ * IRQ number
+ *
+ ********************************************************************************************/
+
+ .macro HANDLER, label, irqno, common
+\label:
+ push r24
+ ldi r24, \irqno
+ rjmp \common
+ .endm
+
+/********************************************************************************************
+ * Name: EXCPT_PROLOGUE
+ *
+ * Description:
+ * Provides the common "prologue" logic that should appear at the beginning of the exception
+ * handler.
+ *
+ * On Entry:
+ * r0 - has already been pushed onto the stack and now holds the IRQ number
+ * sp - Points to the top of the stack
+ * Only the stack is available for storage
+ *
+ * At completion:
+ * Register state is saved on the stack; All registers are available for usage except sp.
+ *
+ ********************************************************************************************/
+
+ .macro EXCPT_PROLOGUE
+ /* Save R1 - The zero register (but might not be zero) */
+
+ push r1
+
+ /* Save the status register on the stack */
+
+ in r1, __SREG__ /* Save the status register */
+ cli /* Disable interrupts */
+ push r1
+
+ /* R1 must be zero for our purposes */
+
+ clr r1
+
+ /* Save r2-r17 - Call-saved, "static" registers */
+
+ push r2
+ push r3
+ push r4
+ push r5
+ push r6
+ push r7
+ push r8
+ push r9
+ push r10
+ push r11
+ push r12
+ push r13
+ push r14
+ push r15
+ push r16
+ push r17
+
+ /* Save r18-r27 - Call-used, "volatile" registers (r24 was saved by
+ * HANDLER, r26-r27 saved later, out of sequence)
+ */
+
+ push r18
+ push r19
+ push r20
+ push r21
+ push r22
+ push r23
+ push r25
+
+ /* Save r28-r29 - Call-saved, "static" registers */
+
+ push r28
+ push r29
+
+ /* Save r30-r31 - Call-used, "volatile" registers */
+
+ push r30
+ push r31
+
+ /* Now save r26-r27 */
+
+ push r26
+ push r27
+
+ /* Finally, save the stack pointer. BUT we want the value of the stack pointer as
+ * it was on entry into this macro. We'll have to subtract to get that value.
+ */
+
+ in r24, __SP_L__
+ in r25, __SP_H__
+ adiw r24, XCPTCONTEXT_REGS
+
+ push r24
+ push r25
+ .endm
+
+/********************************************************************************************
+ * Name: EXCPT_EPILOGUE
+ *
+ * Description:
+ * Provides the "epilogue" logic that should appear at the end of every exception handler.
+ *
+ * On input:
+ * sp points to the address of the register save area (just as left by EXCPT_PROLOGUE).
+ * All registers are available for use.
+ * Interrupts are disabled.
+ *
+ * On completion:
+ * All registers restored
+ *
+ ********************************************************************************************/
+
+ .macro EXCPT_EPILOGUE, regs
+
+ /* We don't need to restore the stack pointer */
+
+ pop r27
+ pop r26
+
+ /* Restore r26-r27 */
+
+ pop r27
+ pop r26
+
+ /* Restore r30-r31 - Call-used, "volatile" registers */
+
+ pop r31
+ pop r30
+
+ /* Restore r28-r29 - Call-saved, "static" registers */
+
+ pop r29
+ pop r28
+
+ /* Restore r18-r27 - Call-used, "volatile" registers (r26-r27 already
+ * restored, r24 will be restored later)
+ */
+
+ pop r25
+ pop r23
+ pop r22
+ pop r21
+ pop r20
+ pop r19
+ pop r18
+
+ /* Restore r2-r17 - Call-saved, "static" registers */
+
+ pop r17
+ pop r16
+ pop r15
+ pop r14
+ pop r13
+ pop r12
+ pop r11
+ pop r10
+ pop r9
+ pop r8
+ pop r7
+ pop r6
+ pop r5
+ pop r4
+ pop r3
+ pop r2
+
+ /* Restore r1 - the "zero" register (that may not be zero) */
+
+ pop r1
+
+ /* Restore the status register (probably enabling interrupts) */
+
+ pop r0 /* Restore the status register */
+ out __SREG__, r0
+
+ /* Finally, restore r0 and r24 - the scratch and IRQ number registers */
+
+ pop r0
+ pop r24
+ .endm
+
+/********************************************************************************************
+ * Name: USER_SAVE
+ *
+ * Description:
+ * Similar to EXPCT_PROLOGUE except that (1) this saves values into a register save
+ * data structure instead of on the stack, (2) the pointer is in r26;r27, and (3)
+ * Call-used registers are not saved.
+ *
+ * On Entry:
+ * X [r26:r27] - Points to the register save structure.
+ * Interrupts are disabled.
+ *
+ * At completion:
+ * Register state is saved on the stack; All registers are available for usage except sp.
+ *
+ ********************************************************************************************/
+
+ .macro USER_SAVE
+
+ /* Save the current stack pointer. */
+
+ in r24, __SP_L__
+ st x+, r24
+ in r25, __SP_H__
+ st x+, r24
+
+ /* Skip over r26-r27 and r30-r31 - Call-used, "volatile" registers */
+
+ adiw r26, 4 /* Four registers: r26-r27 and r30-r31*/
+
+ /* Save r28-r29 - Call-saved, "static" registers */
+
+ st x+, r29
+ st x+, r28
+
+ /* Skip over r18-r27 - Call-used, "volatile" registers (r26-r27 have been skipped) */
+
+ adiw r26, 8 /* Eight registers: r18-r25 */
+
+ /* Save r2-r17 - Call-saved, "static" registers */
+
+ st x+, r17
+ st x+, r16
+ st x+, r15
+ st x+, r14
+ st x+, r13
+ st x+, r12
+ st x+, r11
+ st x+, r10
+ st x+, r9
+ st x+, r8
+ st x+, r7
+ st x+, r6
+ st x+, r5
+ st x+, r4
+ st x+, r3
+ st x+, r2
+
+ /* Set r1 to zero - Function calls must return with r1=0 */
+
+ clr r1
+ st x+, r1
+
+ /* Save the status register (probably not necessary since interrupts are disabled) */
+
+ in r0, __SREG__
+ st x+, r0
+
+ /* Skip R0 and r24 - These are scratch register and Call-used, "volatile" registers */
+ .endm
+
+/********************************************************************************************
+ * Name: TCB_RESTORE
+ *
+ * Description:
+ * Functionally equivalent to EXCPT_EPILOGUE excetp that register save area is not on the
+ * stack but is held in a data structure.
+ *
+ * On input:
+ * X [r26:r27] points to the data structure.
+ * All registers are available for use.
+ * Interrupts are disabled.
+ *
+ * On completion:
+ * All registers restored
+ *
+ ********************************************************************************************/
+
+ .macro TCB_RESTORE, regs
+
+ /* Fetch the new stack pointer and the saved values of X [r26:r27]. Save X on the new
+ * stack where we can recover it later.
+ */
+
+ ld r24, x+ /* Fetch stack pointer (post-incrementing) */
+ out __SP_L__, r24
+ ld r25, x+
+ out __SP_H__, r25
+ ld r25, x+ /* Fetch r26-r27 and save to the new stack */
+ ld r24, x+
+ push r24
+ push r25
+
+ /* Restore r30-r31 - Call-used, "volatile" registers */
+
+ ld r31, x+
+ ld r30, x+
+
+ /* Restore r28-r29 - Call-saved, "static" registers */
+
+ ld r29, x+
+ ld r28, x+
+
+ /* Restore r18-r27 - Call-used, "volatile" registers (r26-r27 have been
+ * moved and r24 will be restore later)
+ */
+
+ ld r25, x+
+ ld r23, x+
+ ld r22, x+
+ ld r21, x+
+ ld r20, x+
+ ld r19, x+
+ ld r18, x+
+
+ /* Restore r2-r17 - Call-saved, "static" registers */
+
+ ld r17, x+
+ ld r16, x+
+ ld r15, x+
+ ld r14, x+
+ ld r13, x+
+ ld r12, x+
+ ld r11, x+
+ ld r10, x+
+ ld r9, x+
+ ld r8, x+
+ ld r7, x+
+ ld r6, x+
+ ld r5, x+
+ ld r4, x+
+ ld r3, x+
+ ld r2, x+
+
+ /* Restore r1 - The "scratch" register */
+
+ ld r1, x+
+
+ /* Restore the status register (probably enabling interrupts) */
+
+ ld r0, x+
+ out __SREG__, r0
+
+ /* Restore r0 and r241 - The scratch and IRQ number registers */
+
+ ld r0, x+
+ ld r24, x+
+
+ /* Finally, recover X [r26-r27] from the the new stack */
+
+ pop r27
+ pop r26
+ .endm
+
+/********************************************************************************************
+ * Name: USE_INTSTACK
+ *
+ * Description:
+ * Switch to the interrupt stack (if enabled in the configuration) and if the nesting level
+ * is equal to 0. Increment the nesting level in any event.
+ *
+ * On Entry:
+ * sp - Current value of the user stack pointer
+ * tmp1, tmp2, and tmp3 are registers that can be used temporarily.
+ * All interrupts should still be disabled.
+ *
+ * At completion:
+ * If the nesting level is 0, then (1) the user stack pointer is saved at the base of the
+ * interrupt stack and sp points to the interrupt stack.
+ * The values of tmp1, tmp2, tmp3, and sp have been altered
+ *
+ ********************************************************************************************/
+
+ .macro USE_INTSTACK, tmp1, tmp2, tmp3
+#if CONFIG_ARCH_INTERRUPTSTACK > 0
+# warning "Not implemented"
+#endif
+ .endm
+
+/********************************************************************************************
+ * Name: RESTORE_STACK
+ *
+ * Description:
+ * Restore the user stack. Not really.. actually only decrements the nesting level. We
+ * always get the new stack pointer for the register save array.
+ *
+ * On Entry:
+ * tmp1 and tmp2 are registers that can be used temporarily.
+ * All interrupts must be disabled.
+ *
+ * At completion:
+ * Current nesting level is decremented
+ * The values of tmp1 and tmp2 have been altered
+ *
+ ********************************************************************************************/
+
+ .macro RESTORE_STACK, tmp1, tmp2
+#if CONFIG_ARCH_INTERRUPTSTACK > 0
+# warning "Not implemented"
+#endif
+ .endm
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_AVR_SRC_AVR_EXCPTMACROS_H */
diff --git a/nuttx/arch/avr/src/avr/up_copystate.c b/nuttx/arch/avr/src/avr/up_copystate.c
new file mode 100644
index 000000000..5423202f2
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/up_copystate.c
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/avr/src/avr/up_copystate.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+
+#include <stdint.h>
+#include <arch/irq.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_copystate
+ ****************************************************************************/
+
+/* Really just a memcpy */
+
+void up_copystate(uint8_t *dest, uint8_t *src)
+{
+ int i;
+
+ /* The state is copied from the stack to the TCB, but only a reference is
+ * passed to get the state from the TCB. So the following check avoids
+ * copying the TCB save area onto itself:
+ */
+
+ if (src != dest)
+ {
+ for (i = 0; i < XCPTCONTEXT_REGS; i++)
+ {
+ *dest++ = *src++;
+ }
+ }
+}
+
diff --git a/nuttx/arch/avr/src/avr/up_switchcontext.S b/nuttx/arch/avr/src/avr/up_switchcontext.S
new file mode 100755
index 000000000..b31173456
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/up_switchcontext.S
@@ -0,0 +1,134 @@
+/************************************************************************************
+ * arch/avr/src/avr/up_switchcontext.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+
+#include "excptmacros.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Global Symbols
+ ************************************************************************************/
+
+ .file "up_switchcontext.S"
+
+/************************************************************************************
+ * Macros
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: up_switchcontext
+ *
+ * Description:
+ * Save the current thread context and restore the specified context. The full
+ * C function prototype is:
+ *
+ * void up_switchcontext(uint8_t *saveregs, uint8_t *restoreregs);
+ *
+ * On Entry:
+ * r24-r25: savregs
+ * r22-r23: restoreregs
+ *
+ * Return:
+ * up_switchcontext forces a context switch to the task "canned" in restoreregs.
+ * It does not 'return' in the normal sense, rather, it will context switch back
+ * to the function point. When it does 'return,' it is because the blocked
+ * task hat was "pickeled" in the saveregs "can" is again ready to run and has
+ * execution priority.
+ *
+ * Assumptions:
+ * global interrupts disabled by the caller.
+ *
+ ************************************************************************************/
+
+ .text
+ .globl up_switchcontext
+ .func up_switchcontext
+up_switchcontext:
+ /* Use X ]r26:r27] to reference the save structure. (X is Call-used) */
+
+ movw r26, r24
+
+ /* Save the context to saveregs */
+
+ USER_SAVE
+
+ /* Then fall through to do the full context restore with r24-r5 = restoreregs */
+
+ movw r24, r22
+ .endfunc
+
+/****************************************************************************
+ * Name: up_fullcontextrestore
+ *
+ * Descripion:
+ * Restore the full-running context of a thread.
+ *
+ * Input Parameters:
+ * r24-r25 = A pointer to the register save area of the thread to be restored.
+ *
+ * C Prototype:
+ * void up_fullcontextrestore(uint8_t *regs);
+ *
+ * Assumptions:
+ * Interrupts are disabled.
+ *
+ ****************************************************************************/
+
+ .text
+ .global up_fullcontextrestore
+ .func up_fullcontextrestore
+up_fullcontextrestore:
+ /* Use X ]r26:r27] to reference the restore structure. */
+
+ movw r26, r24
+
+ /* Restore the context from the TCB saved registers */
+
+ TCB_RESTORE
+ .endfunc
+ .end
+
diff --git a/nuttx/arch/avr/src/avr32/up_copystate.c b/nuttx/arch/avr/src/avr32/up_copystate.c
index ef8d5f3cb..e3e4da054 100644
--- a/nuttx/arch/avr/src/avr32/up_copystate.c
+++ b/nuttx/arch/avr/src/avr32/up_copystate.c
@@ -41,7 +41,6 @@
#include <stdint.h>
-#include "os_internal.h"
#include "up_internal.h"
/****************************************************************************
diff --git a/nuttx/arch/avr/src/avr32/up_exceptions.S b/nuttx/arch/avr/src/avr32/up_exceptions.S
index 4a7ade6fd..e104a2370 100755
--- a/nuttx/arch/avr/src/avr32/up_exceptions.S
+++ b/nuttx/arch/avr/src/avr32/up_exceptions.S
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/avr32/src/avr32/up_exceptions.S
+ * arch/avr/src/avr32/up_exceptions.S
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>