summaryrefslogtreecommitdiff
path: root/nuttx/arch/mips/src/mips32
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-20 16:19:01 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-20 16:19:01 +0000
commitf943a6e94a7caa69aad320ec610ffb33c8686919 (patch)
tree1351d134abaf1d5a0bf8ef5e88c92fb3b0e2fabe /nuttx/arch/mips/src/mips32
parentbccc2e256e4664cb3010a678722866a71e2fafc5 (diff)
downloadpx4-nuttx-f943a6e94a7caa69aad320ec610ffb33c8686919.tar.gz
px4-nuttx-f943a6e94a7caa69aad320ec610ffb33c8686919.tar.bz2
px4-nuttx-f943a6e94a7caa69aad320ec610ffb33c8686919.zip
Fleshing out PIC32 port
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3632 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/mips/src/mips32')
-rwxr-xr-xnuttx/arch/mips/src/mips32/up_bevhandler.S103
-rwxr-xr-xnuttx/arch/mips/src/mips32/up_inthandler.S104
2 files changed, 0 insertions, 207 deletions
diff --git a/nuttx/arch/mips/src/mips32/up_bevhandler.S b/nuttx/arch/mips/src/mips32/up_bevhandler.S
deleted file mode 100755
index 3fbe98d53..000000000
--- a/nuttx/arch/mips/src/mips32/up_bevhandler.S
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- * arch/mips/src/mips32/up_bevexcptn.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/mips32/registers.h>
-
-#include "chip/excptmacros.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Global Symbols
- ****************************************************************************/
-
- .file "up_bevexcptn.S"
- .global up_dobev
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-/****************************************************************************
- * Name: _bev_exception
- *
- * Description:
- * Boot Exception Vector Handler. Jumps to bev_handler
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * Does not return
- *
- ****************************************************************************/
-
- .section .bev_excpt,"ax",@progbits
- .set noreorder
- .ent _bev_exception
-_bev_exception:
- la k0, _bev_handler
- jr k0
- nop
- .end _bev_exception
-
-/****************************************************************************
- * Name: _bev_handler
- *
- * Description:
- * BEV exception handler
- *
- ****************************************************************************/
-
- .section .bev_handler, "ax", @progbits
- .set noreorder
- .ent _bev_handler
-_bev_handler:
- EXCPT_PROLOGUE t0 /* Save registers on stack, enable nested interrupts */
- move a0, sp /* Pass register save structure as the parameter 1 */
- USE_INTSTACK t0, t1, t2 /* Switch to the interrupt stack */
- la t0, up_dobev /* Call up_dobev(regs) */
- jalr t0, ra
- di /* Disable interrupts */
- RESTORE_STACK t0, t1 /* Undo the operations of USE_STACK */
- EXCPT_EPILOGUE v0 /* Return to the context returned by up_dobev() */
- .end _bev_handler
diff --git a/nuttx/arch/mips/src/mips32/up_inthandler.S b/nuttx/arch/mips/src/mips32/up_inthandler.S
deleted file mode 100755
index bf43f5af9..000000000
--- a/nuttx/arch/mips/src/mips32/up_inthandler.S
+++ /dev/null
@@ -1,104 +0,0 @@
-/****************************************************************************
- * arch/mips/src/mips32/up_genexcptn.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/mips32/registers.h>
-
-#include "chip/excptmacros.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Global Symbols
- ****************************************************************************/
-
- .file "up_genexcptn.S"
- .global _int_handler
- .global up_decodeirq
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-/****************************************************************************
- * Name: _int_exception
- *
- * Description:
- * Interrupt Exception Vector Handler. Jumps to _int_handler
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * Does not return
- *
- ****************************************************************************/
-
- .section .int_excpt,"ax",@progbits
- .set noreorder
- .ent _int_exception
-_int_exception:
- la k0, _int_handler
- jr k0
- nop
- .end _int_exception
-
-/****************************************************************************
- * Name: _int_handler
- *
- * Description:
- * Interrupt exception handler
- *
- ****************************************************************************/
-
- .section .int_handler, "ax", @progbits
- .set noreorder
- .ent _int_handler
-_int_handler:
- EXCPT_PROLOGUE t0 /* Save registers on stack, enable nested interrupts */
- move a0, sp /* Pass register save structure as the parameter 1 */
- USE_INTSTACK t0, t1, t2 /* Switch to the interrupt stack */
- la t0, up_decodeirq /* Call up_decodeirq(regs) */
- jalr t0, ra
- di /* Disable interrupts */
- RESTORE_STACK t0, t1 /* Undo the operations of USE_STACK */
- EXCPT_EPILOGUE v0 /* Return to the context returned by up_decodeirq() */
- .end _int_handler