From 2d1343700382c3ef94e8ba1eba4b1d43918efbd7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 20 May 2011 17:51:11 +0000 Subject: Add PIC32 interrupt decode logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3633 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/mips/src/pic32mx/Make.defs | 4 +- nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c | 3 +- nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c | 172 +++++++++++++++++++ nuttx/arch/mips/src/pic32mx/pic32mx-dobev.c | 195 ++++++++++++++++++++++ nuttx/arch/mips/src/pic32mx/pic32mx-head.S | 54 +++--- nuttx/arch/mips/src/pic32mx/pic32mx-internal.h | 34 +++- nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c | 8 +- 7 files changed, 429 insertions(+), 41 deletions(-) create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-dobev.c (limited to 'nuttx/arch/mips') diff --git a/nuttx/arch/mips/src/pic32mx/Make.defs b/nuttx/arch/mips/src/pic32mx/Make.defs index 4cfcc8d3a..193834974 100755 --- a/nuttx/arch/mips/src/pic32mx/Make.defs +++ b/nuttx/arch/mips/src/pic32mx/Make.defs @@ -61,8 +61,8 @@ endif # Required PIC32MX files CHIP_ASRCS = -CHIP_CSRCS = pic32mx-irq.c pic32mx-clockconfig.c pic32mx-lowconsole.c pic32mx-lowinit.c \ - pic32mx-serial.c pic32mx-timerisr.c +CHIP_CSRCS = pic32mx-irq.c pic32mx-clockconfig.c pic32mx-decodeirq.c pic32mx-dobev.c \ + pic32mx-lowconsole.c pic32mx-lowinit.c pic32mx-serial.c pic32mx-timerisr.c # Configuration-dependent PIC32MX files diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c b/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c index 342dd4bf0..de2bc8dc2 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c @@ -79,7 +79,8 @@ * Name: pic32mx_clockconfig * * Description: - * Called to initialize the PIC32MX clocking using the settings in board.h. + * Called by pic32mx_lowinitto initialize the PIC32MX clocking using the + * settings in board.h. * **************************************************************************/ diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c b/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c new file mode 100644 index 000000000..61ac69817 --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c @@ -0,0 +1,172 @@ +/**************************************************************************** + * arch/mips/src/pic32mx/pic32mx-decodeirq.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "os_internal.h" + +#include "pic32mx-int.h" +#include "pic32mx-internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pic32mx_decodeirq + * + * Description: + * Called from assembly language logic when an interrrupt exception occurs. + * This function decodes and dispatches the interrupt. + * + ****************************************************************************/ + +uint32_t *pic32mx_decodeirq(uint32_t *regs) +{ +#ifdef CONFIG_SUPPRESS_INTERRUPTS + + up_ledon(LED_INIRQ); + PANIC(OSERR_ERREXCEPTION); + up_ledoff(LED_INIRQ); /* Won't get here */ + return regs; + +#else + uint32_t *savestate; + uint32_t regval; + int irq; + + /* If the board supports LEDs, turn on an LED now to indicate that we are + * processing an interrupt. + */ + + up_ledon(LED_INIRQ); + + /* Save the current value of current_regs (to support nested interrupt + * handling). Then set current_regs to regs, indicating that this is + * the interrupted context that is being processed now. + */ + + savestate = (uint32_t*)current_regs; + current_regs = regs; + + /* Loop while there are pending interrupts with priority greater than zero */ + + for (;;) + { + /* Read the INTSTAT register. This register contains both the priority + * and the interrupt vector number. + */ + + regval = getreg32(PIC32MX_INT_INTSTAT); + if ((regval & INT_INTSTAT_RIPL_MASK) == 0) + { + /* Break out of the loop when the priority is zero meaning that + * there are no further pending interrupts. + */ + + break; + } + + /* Get the vector number. The IRQ numbers have been arranged so that + * vector numbers and NuttX IRQ numbers are the same value. + */ + + irq = ((regval) & INT_INTSTAT_VEC_MASK) >> INT_INTSTAT_VEC_SHIFT; + + /* Mask and acknowledge the interrupt */ + + up_maskack_irq(irq); + + /* Deliver the IRQ */ + + irq_dispatch(irq, regs); + + /* Unmask the last interrupt (global interrupt below the current interrupt + * level are are still disabled) + */ + + up_enable_irq(irq); + } + + /* If a context switch occurred while processing the interrupt then + * current_regs may have change value. If we return any value different + * from the input regs, then the lower level will know that a context + * switch occurred during interrupt processing. + */ + + regs = (uint32_t*)current_regs; + + /* Restore the previous value of current_regs. NULL would indicate that + * we are no longer in an interrupt handler. It will be non-NULL if we + * are returning from a nested interrupt. + */ + + current_regs = savestate; + if (current_regs == NULL) + { + up_ledoff(LED_INIRQ); + } + + return regs; +#endif +} diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-dobev.c b/nuttx/arch/mips/src/pic32mx/pic32mx-dobev.c new file mode 100644 index 000000000..cd12cf40a --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-dobev.c @@ -0,0 +1,195 @@ +/**************************************************************************** + * arch/mips/src/pic32mx/pic32mx-dobev.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "os_internal.h" + +#include "pic32mx-int.h" +#include "pic32mx-internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/************************************************************************************ + * Name: pic32mx_dobev + * + * Description: + * Called from assembly language logic on all other exceptions. + * + ************************************************************************************/ + +uint32_t *pic32mx_dobev(uint32_t *regs) +{ +#ifdef CONFIG_DEBUG + uint32_t cause; + uint32_t epc; +#endif + + /* If the board supports LEDs, turn on an LED now to indicate that we are + * processing an interrupt. + */ + + up_ledon(LED_INIRQ); + +#ifdef CONFIG_DEBUG + /* Get the cause of the exception from the CAUSE register */ + + asm volatile("\tmfc0 %0,$13,0\n" : "=r"(cause)); + asm volatile("\tmfc0 %0,$14,0\n" : "=r"(epc)); + +#ifdef CONFIG_DEBUG_VERBOSE + switch (cause & CP0_CAUSE_EXCCODE_MASK) + { + case CP0_CAUSE_EXCCODE_INT: /* Interrupt */ + llvdbg("EXCEPTION: Interrupt" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_TLBL: /* TLB exception (load or instruction fetch) */ + llvdbg("EXCEPTION: TLB exception (load or instruction fetch)" + " CAUSE:%08x EPC:%0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_TLBS: /* TLB exception (store) */ + llvdbg("EXCEPTION: TLB exception (store)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_ADEL: /* Address error exception (load or instruction fetch) */ + llvdbg("EXCEPTION: Address error exception (load or instruction fetch)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_ADES: /* Address error exception (store) */ + llvdbg("EXCEPTION: Address error exception (store)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_IBE: /* Bus error exception (instruction fetch) */ + llvdbg("EXCEPTION: Bus error exception (instruction fetch)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_DBE: /* Bus error exception (data reference: load or store) */ + llvdbg("EXCEPTION: Bus error exception (data reference: load or store)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_SYS: /* Syscall exception */ + llvdbg("EXCEPTION: Syscall exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_BP: /* Breakpoint exception */ + llvdbg("EXCEPTION: Breakpoint exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_RI: /* Reserved instruction exception */ + llvdbg("EXCEPTION: Reserved instruction exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_CPU: /* Coprocessor Unusable exception */ + llvdbg("EXCEPTION: Coprocessor Unusable exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_OV: /* Arithmetic Overflow exception */ + llvdbg("EXCEPTION: Arithmetic Overflow exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_TR: /* Trap exception */ + llvdbg("EXCEPTION: Trap exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_FPE: /* Floating point exception */ + llvdbg("EXCEPTION: Floating point exception" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_C2E: /* Precise Coprocessor 2 exceptions */ + llvdbg("EXCEPTION: Precise Coprocessor 2 exceptions" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_MDMX: /* MDMX Unusable (MIPS64) */ + llvdbg("EXCEPTION: MDMX Unusable (MIPS64)" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_WATCH: /* WatchHi/WatchLo address */ + llvdbg("EXCEPTION: WatchHi/WatchLo address" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_MCHECK: /* Machine check */ + llvdbg("EXCEPTION: Machine check" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + case CP0_CAUSE_EXCCODE_CACHEERR: /* Cache error */ + llvdbg("EXCEPTION: Cache error" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + default: + llvdbg("EXCEPTION: Unknown" + " CAUSE: %08x EPC: %0ex\n", cause, epc); + break; + } +#else + lldbg("EXCEPTION: CAUSE: %08x EPC: %0ex\n", cause, epc); +#endif +#endif + + /* Crash */ + + PANIC(OSERR_ERREXCEPTION); + return regs; /* Won't get here */ +} diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S index e52e2549f..b315df2f7 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S @@ -122,10 +122,10 @@ /* Imported symbols */ .global os_start - .global up_dobev - .global up_decodeirq + .global pic32mx_dobev + .global pic32mx_decodeirq #ifdef CONFIG_PIC32MX_NMIHANDLER - .global up_donmi + .global pic32mx_donmi #endif /**************************************************************************** @@ -419,7 +419,7 @@ __start: * Name: _bev_handler * * Description: - * BEV exception handler. Calls up_dobev() + * BEV exception handler. Calls pic32mx_dobev() * ****************************************************************************/ @@ -427,14 +427,14 @@ __start: .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) */ + 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, pic32mx_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() */ + 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 /**************************************************************************** @@ -449,21 +449,21 @@ _bev_handler: .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) */ + 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, pic32mx_decodeirq /* Call pic32mx_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() */ + di /* Disable interrupts */ + RESTORE_STACK t0, t1 /* Undo the operations of USE_STACK */ + EXCPT_EPILOGUE v0 /* Return to the context returned by pic32mx_decodeirq() */ .end _int_handler /**************************************************************************** * Name: _nmi_handler * * Description: - * NMI exception handler. Calls up_donmi + * NMI exception handler. Calls pic32mx_donmi * ****************************************************************************/ @@ -472,14 +472,14 @@ _int_handler: .set noreorder .ent _nmi_handler _nmi_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_donmi /* Call up_donmi(regs) */ + 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, pic32mx_donmi /* Call up_donmi(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_donmi() */ + di /* Disable interrupts */ + RESTORE_STACK t0, t1 /* Undo the operations of USE_STACK */ + EXCPT_EPILOGUE v0 /* Return to the context returned by pic32mx_donmi() */ .end _nmi_handler #endif @@ -501,7 +501,7 @@ _nmi_handler: __start_nuttx: /* Perform low level initialization */ - la t0, up_lowinit + la t0, pic32mx_lowinit jalr t0, ra nop diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h index da6e8b1f5..6682eb752 100755 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h @@ -119,11 +119,22 @@ extern "C" { * Public Function Prototypes ************************************************************************************/ +/************************************************************************************ + * Name: pic32mx_lowinit + * + * Description: + * This performs basic low-level initialization of the system. + * + ************************************************************************************/ + +EXTERN void pic32mx_lowinit(void); + /************************************************************************************ * Name: pic32mx_clockconfig * * Description: - * Called to initialize the PIC32MX clocking using the settings in board.h. + * Called by pic32mx_lowinit to initialize the PIC32MX clocking using the settings + * in board.h. * ************************************************************************************/ @@ -134,7 +145,8 @@ EXTERN void pic32mx_clockconfig(void); * * Description: * Performs low level initialization of the console UART. This UART done early so - * that the serial console is available for debugging very early in the boot sequence. + * that the serial console is available for debugging very early in the boot + * sequence. * ************************************************************************************/ @@ -163,7 +175,7 @@ EXTERN void pic32mx_uartreset(uintptr_t uart_base); #ifdef HAVE_UART_DEVICE EXTERN void pic32mx_uartconfigure(uintptr_t uart_base, uint32_t baud, unsigned int parity, unsigned int nbits, - bool stop2); + bool stop2); #endif /************************************************************************************ @@ -192,15 +204,25 @@ EXTERN void pic32mx_gpioirqinitialize(void); EXTERN void pic32mx_boardinitialize(void); /************************************************************************************ - * Name: up_decodeirq + * Name: pic32mx_decodeirq * * Description: - * Called from assembly language logic when and interrrupt exception occurs. This + * Called from assembly language logic when an interrrupt exception occurs. This * function decodes and dispatches the interrupt. * ************************************************************************************/ -EXTERN uint32_t *up_decodeirq(uint32_t *regs); +EXTERN uint32_t *pic32mx_decodeirq(uint32_t *regs); + +/************************************************************************************ + * Name: pic32mx_dobev + * + * Description: + * Called from assembly language logic on all other exceptions. + * + ************************************************************************************/ + +EXTERN uint32_t *pic32mx_dobev(uint32_t *regs); /************************************************************************************ * Name: pic32mx_configgpio diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c index cecaf4146..f4fd904ad 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c @@ -71,16 +71,14 @@ **************************************************************************/ /************************************************************************** - * Name: up_lowinit + * Name: pic32mx_lowinit * * Description: - * This performs basic initialization of the USART used for the serial - * console. Its purpose is to get the console output availabe as soon - * as possible. + * This performs basic low-level initialization of the system. * **************************************************************************/ -void up_lowinit(void) +void pic32mx_lowinit(void) { /* Initialize MCU clocking */ -- cgit v1.2.3