summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-14 03:24:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-14 03:24:18 +0000
commit030bad1299d27f14f1c193d61c85ccbf12a698dc (patch)
treea77dd06fe144600deaa20523aedb4de30676ca3d /nuttx/arch/avr
parentca3a98e8fc6457ce247f4b490477b7def161220f (diff)
downloadpx4-nuttx-030bad1299d27f14f1c193d61c85ccbf12a698dc.tar.gz
px4-nuttx-030bad1299d27f14f1c193d61c85ccbf12a698dc.tar.bz2
px4-nuttx-030bad1299d27f14f1c193d61c85ccbf12a698dc.zip
Beginning of context switch logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3012 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr')
-rw-r--r--nuttx/arch/avr/include/avr32/irq.h43
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/Make.defs4
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_adc.h74
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_pwm.h74
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_ssc.h74
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_tc.h74
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_usbb.h74
-rwxr-xr-xnuttx/arch/avr/src/avr32/up_exceptions.S55
-rwxr-xr-xnuttx/arch/avr/src/avr32/up_fullcontextrestore.S113
9 files changed, 567 insertions, 18 deletions
diff --git a/nuttx/arch/avr/include/avr32/irq.h b/nuttx/arch/avr/include/avr32/irq.h
index 47947be2c..b7819032e 100644
--- a/nuttx/arch/avr/include/avr32/irq.h
+++ b/nuttx/arch/avr/include/avr32/irq.h
@@ -51,11 +51,46 @@
* Definitions
****************************************************************************/
-/* Register state save array indices */
-
-/* Size of the register state save array */
+/* Register state save array indices.
+ *
+ * The following registers are saved by the AVR32 hardware (for the case of
+ * interrupts only). Note the registers are order in the opposite order the
+ * they appear in memory (i.e., in the order of increasing address) because
+ * this makes it easier to following the ordering of pushing on a push-down
+ * stack.
+ */
+
+#define REG_R8 16
+#define REG_R9 15
+#define REG_R10 14
+#define REG_R11 13
+#define REG_R12 12
+#define REG_R14 11
+#define REG_R15 10
+#define REG_SR 9
+
+#define REG_LR REG_R14
+#define REG_PC REG_R15
+
+/* Additional registers saved in order have the full CPU context */
+
+#define REG_R13 8
+#define REG_SP REG_R13
+
+#define REG_R0 7
+#define REG_R1 6
+#define REG_R2 5
+#define REG_R3 4
+#define REG_R4 3
+#define REG_R5 2
+#define REG_R6 1
+#define REG_R7 0
+
+/* Size of the register state save array (in 32-bit words) */
+
+#define INTCONTEXT_REGS 8 /* r8-r12, lr, pc, sr */
+#define XCPTCONTEXT_REGS 17 /* Plus r0-r7, sp */
-#define XCPTCONTEXT_REGS 1
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/avr/src/at91uc3/Make.defs b/nuttx/arch/avr/src/at91uc3/Make.defs
index 58c425866..a3369a606 100755
--- a/nuttx/arch/avr/src/at91uc3/Make.defs
+++ b/nuttx/arch/avr/src/at91uc3/Make.defs
@@ -39,14 +39,14 @@ HEAD_ASRC = up_nommuhead.S
# Common AVR/AVR32 files
-CMN_ASRCS = up_exceptions.S
+CMN_ASRCS = up_exceptions.S up_fullcontextrestore.S
CMN_CSRCS = up_assert.c up_allocateheap.c up_blocktask.c up_copystate.c \
up_createstack.c up_mdelay.c up_udelay.c up_exit.c up_idle.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
- up_usestack.c up_doirq.c
+ up_usestack.c up_doirq.c
# Required AT91UC3 files
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_adc.h b/nuttx/arch/avr/src/at91uc3/at91uc3_adc.h
new file mode 100755
index 000000000..a565630ca
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_adc.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_adc.h
+ *
+ * Copyright (C) 2010 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_AT91UC3_AT91UC3_ADC_H
+#define __ARCH_AVR_SRC_AT91UC3_AT91UC3_ADC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Addresses ***************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Bit-field Definitions ***************************************************/
+
+#warning "Missing Logic"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT91UC3_AT91UC3_ADC_H */
+
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_pwm.h b/nuttx/arch/avr/src/at91uc3/at91uc3_pwm.h
new file mode 100755
index 000000000..59495a334
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_pwm.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_pwm.h
+ *
+ * Copyright (C) 2010 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_AT91UC3_AT91UC3_PWM_H
+#define __ARCH_AVR_SRC_AT91UC3_AT91UC3_PWM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Addresses ***************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Bit-field Definitions ***************************************************/
+
+#warning "Missing Logic"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT91UC3_AT91UC3_PWM_H */
+
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_ssc.h b/nuttx/arch/avr/src/at91uc3/at91uc3_ssc.h
new file mode 100755
index 000000000..ea370f8f1
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_ssc.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_ssc.h
+ *
+ * Copyright (C) 2010 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_AT91UC3_AT91UC3_SSC_H
+#define __ARCH_AVR_SRC_AT91UC3_AT91UC3_SSC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#warning "Missing logic"
+
+/* Register Addresses ***************************************************************/
+
+#warning "Missing logic"
+
+/* Register Bit-field Definitions ***************************************************/
+
+#warning "Missing logic"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT91UC3_AT91UC3_SSC_H */
+
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_tc.h b/nuttx/arch/avr/src/at91uc3/at91uc3_tc.h
new file mode 100755
index 000000000..7071fab1b
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_tc.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_tc.h
+ *
+ * Copyright (C) 2010 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_AT91UC3_AT91UC3_TC_H
+#define __ARCH_AVR_SRC_AT91UC3_AT91UC3_TC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Addresses ***************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Bit-field Definitions ***************************************************/
+
+#warning "Missing Logic"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT91UC3_AT91UC3_TC_H */
+
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_usbb.h b/nuttx/arch/avr/src/at91uc3/at91uc3_usbb.h
new file mode 100755
index 000000000..09ee1c5f8
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_usbb.h
@@ -0,0 +1,74 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_usbb.h
+ *
+ * Copyright (C) 2010 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_AT91UC3_AT91UC3_USBB_H
+#define __ARCH_AVR_SRC_AT91UC3_AT91UC3_USBB_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Addresses ***************************************************************/
+
+#warning "Missing Logic"
+
+/* Register Bit-field Definitions ***************************************************/
+
+#warning "Missing Logic"
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AT91UC3_AT91UC3_USBB_H */
+
diff --git a/nuttx/arch/avr/src/avr32/up_exceptions.S b/nuttx/arch/avr/src/avr32/up_exceptions.S
index 56941f764..a314e800c 100755
--- a/nuttx/arch/avr/src/avr32/up_exceptions.S
+++ b/nuttx/arch/avr/src/avr32/up_exceptions.S
@@ -40,9 +40,6 @@
#include <nuttx/config.h>
#include <arch/avr32/avr32.h>
-#include "up_internal.h"
-#include "up_arch.h"
-
/****************************************************************************
* External Symbols
****************************************************************************/
@@ -209,18 +206,52 @@ avr32_excptcommon:
* Common Event Handling Logic
****************************************************************************/
-/* After this point, logic to manage interrupts and exceptions is equivalent.
- * Here we have:
- *
- * R8-R12, LR, SR, and the PC on the stack.
- * R12 holds the IRQ number to be dispatched.
- *
- * This function will finish construction of the register save structure and
- * call the IRQ dispatching logic.
- */
+/* After this point, logic to manage interrupts and exceptions is */
+/* equivalent. Here we have: */
+/* */
+/* R8-R12, LR, SR, and the PC on the stack. */
+/* R12 holds the IRQ number to be dispatched. */
+/* */
+/* The context save area looks like this: */
+/* xx xx xx xx xx xx xx xx xx SR PC LR 12 11 10 09 08 */
+/* ^ +8*4 */
+/* This function will finish construction of the register save structure */
+/* and call the IRQ dispatching logic. */
avr32_common:
+ /* Save the SP (as it was before the interrupt) in the conext save */
+ /* structure. */
+ /* xx xx xx xx xx xx xx xx SP SR PC LR 12 11 10 09 08 */
+ /* ^sp */
+
+ mov r8, sp
+ sub r8, -8*4
+ st.w --sp, r8
+
+ /* Saving R0-R7 is all that is left to complete the context save. */
+ /* 07 06 05 04 03 02 01 00 SP SR PC LR 12 11 10 09 08 */
+ /* ^sp */
+
+ stm --sp, r0-r7
+
+ /* Now call up_doirq passing the IRQ number in r12 and the base address */
+ /* of the register context save area in r13. */
+
+ mov r12, sp
+ mcall .Lup_doirq
+
#warning "Missing Logic"
rjmp $
+
+ /* On return, r12 will hold the new address of the register context save
+ * area. On an interrupt contex switch, this will (1) not be the same
+ * as the value of r12 passed to up_doirq(), and (2) may not reside on
+ * a stack.
+ */
+
+#warning "Missing Logic"
+
+.Lup_doirq:
+ .word up_doirq
.end
diff --git a/nuttx/arch/avr/src/avr32/up_fullcontextrestore.S b/nuttx/arch/avr/src/avr32/up_fullcontextrestore.S
new file mode 100755
index 000000000..6969b0bed
--- /dev/null
+++ b/nuttx/arch/avr/src/avr32/up_fullcontextrestore.S
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * arch/avr32/src/avr32/up_fullcontextrestore.S
+ *
+ * Copyright (C) 2010 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/avr32/avr32.h>
+
+/****************************************************************************
+ * External Symbols
+ ****************************************************************************/
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_fullcontextrestore
+ *
+ * C Prototype:
+ * void up_fullcontextrestore(uint32_t *regs);
+ *
+ ****************************************************************************/
+
+ .text
+ .global up_fullcontextrestore
+ .type up_fullcontextrestore, @function
+up_fullcontextrestore:
+
+ /* Initially, r12 points to the r7 save area. Restore r0-r7. */
+ /* 07 06 05 04 03 02 01 00 xx xx xx xx xx xx xx xx xx */
+ /* ^r12 */
+
+ ldm r12++, r0-r7
+
+ /* Now, r12 points to the SP (r13) save area. Recover the value of */
+ /* the stack pointer (r13). We will need to save some temporaries on */
+ /* the final stack. */
+ /* 07 06 05 04 03 02 01 00 SP xx xx xx xx xx xx xx xx */
+ /* ^r12 */
+
+ ld.w sp, r12++
+
+ /* Now r12 points to the SR save area. Skip over the SR for now. */
+ /* 07 06 05 04 03 02 01 00 SP xx xx xx xx xx xx xx xx */
+ /* ^r12 */
+
+ sub r12, -2*4
+
+ /* Get the pc, lr, and r12 (in r8, r9, and r10) and move them to the */
+ /* stack. We can now use r12 and lr as scratch registers. */
+ /* 07 06 05 04 03 02 01 00 SP xx PC LR 12 xx xx xx xx */
+ /* ^r12 */
+
+ ldm r12++, r8-r10
+ stm --sp, r8-r10
+
+ /* Now r12 now points to the r11 save area. Restore r8-r11. */
+ /* 07 06 05 04 03 02 01 00 SP xx PC LR 12 11 10 09 08 */
+ /* ^r12 */
+
+ ldm r12++, r8-r11
+
+ /* r12 now points +4 beyond the end of the register save area. Restore */
+ /* SR. */
+ /* 07 06 05 04 03 02 01 00 SP SR PC LR 12 11 10 09 08 */
+ /* ^r12-4*8 ^r12 */
+
+ ld.w lr, r12[-4*8]
+ mtsr AVR32_SR, lr
+
+ /* Restore PC, LR and r12. Hmmm.. I need to study the behaviour of ldm */
+ /* when r12,lr, and pc on in ldm reglist16. I'm not sure that I want */
+ /* that behavior. */
+
+/* ldm sp++, r12, lr, pc */
+ ldm sp++, r12, lr
+ ld.w pc, sp++
+ .end