From f943a6e94a7caa69aad320ec610ffb33c8686919 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 20 May 2011 16:19:01 +0000 Subject: Fleshing out PIC32 port git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3632 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/mips/src/common/up_initialize.c | 2 - nuttx/arch/mips/src/common/up_internal.h | 119 ++-- nuttx/arch/mips/src/mips32/up_bevhandler.S | 103 --- nuttx/arch/mips/src/mips32/up_inthandler.S | 104 --- nuttx/arch/mips/src/pic32mx/Make.defs | 5 +- nuttx/arch/mips/src/pic32mx/excptmacros.h | 9 +- nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c | 92 +++ nuttx/arch/mips/src/pic32mx/pic32mx-config.h | 103 +++ nuttx/arch/mips/src/pic32mx/pic32mx-head.S | 220 ++++++- nuttx/arch/mips/src/pic32mx/pic32mx-internal.h | 60 +- nuttx/arch/mips/src/pic32mx/pic32mx-lowconsole.c | 204 ++++++ nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c | 106 +++ nuttx/arch/mips/src/pic32mx/pic32mx-serial.c | 766 ++++++++++++++++++++++ 13 files changed, 1584 insertions(+), 309 deletions(-) delete mode 100755 nuttx/arch/mips/src/mips32/up_bevhandler.S delete mode 100755 nuttx/arch/mips/src/mips32/up_inthandler.S create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c create mode 100755 nuttx/arch/mips/src/pic32mx/pic32mx-config.h create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-lowconsole.c create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c create mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-serial.c (limited to 'nuttx/arch/mips') diff --git a/nuttx/arch/mips/src/common/up_initialize.c b/nuttx/arch/mips/src/common/up_initialize.c index b51319175..93af8667b 100644 --- a/nuttx/arch/mips/src/common/up_initialize.c +++ b/nuttx/arch/mips/src/common/up_initialize.c @@ -153,8 +153,6 @@ void up_initialize(void) #ifdef CONFIG_USE_SERIALDRIVER up_serialinit(); -#elif defined(CONFIG_DEV_LOWCONSOLE) - lowconsole_init(); #endif /* Initialize the netwok */ diff --git a/nuttx/arch/mips/src/common/up_internal.h b/nuttx/arch/mips/src/common/up_internal.h index df10ae9e6..2e4431fa5 100755 --- a/nuttx/arch/mips/src/common/up_internal.h +++ b/nuttx/arch/mips/src/common/up_internal.h @@ -95,17 +95,15 @@ typedef void (*up_vector_t)(void); ****************************************************************************/ #ifndef __ASSEMBLY__ -/* This holds a references to the current interrupt level - * register storage structure. If is non-NULL only during - * interrupt processing. +/* This holds a references to the current interrupt level register storage + * structure. If is non-NULL only during interrupt processing. */ extern volatile uint32_t *current_regs; -/* This is the beginning of heap as provided from up_head.S. - * This is the first address in DRAM after the loaded - * program+bss+idle stack. The end of the heap is - * CONFIG_DRAM_END +/* This is the beginning of heap as provided from up_head.S. This is the + * first address in DRAM after the loaded program+bss+idle stack. The end + * of the heap is CONFIG_DRAM_END */ extern uint32_t g_heapbase; @@ -155,27 +153,22 @@ extern uint32_t _bmxdupba_address; /* BMX register setting */ ****************************************************************************/ #ifndef __ASSEMBLY__ +/* Common Functions *********************************************************/ +/* Common functions define in arch/mips/src/common. These may be replaced + * with chip-specific functions of the same name if needed. See also + * functions prototyped in include/nuttx/arch.h. + */ -/* Defined in files with the same name as the function */ +/* Context switching */ -extern void up_boot(void); extern void up_copystate(uint32_t *dest, uint32_t *src); -extern void up_irqinitialize(void); -#ifdef CONFIG_ARCH_DMA -extern void weak_function up_dmainitialize(void); -#endif -extern void up_sigdeliver(void); -extern int up_timerisr(int irq, uint32_t *regs); -extern void up_lowputc(char ch); -extern void up_puts(const char *str); -extern void up_lowputs(const char *str); -/* Two alternative interrupt handling functions */ +/* Serial output */ -extern uint32_t *up_decodeirq(uint32_t *regs); -extern uint32_t *up_doirq(int irq, uint32_t *regs); +extern void up_puts(const char *str); +extern void up_lowputs(const char *str); -/* Defined in up_dumpstate.c */ +/* Debug */ #ifdef CONFIG_ARCH_STACKDUMP extern void up_dumpstate(void); @@ -183,7 +176,30 @@ extern void up_dumpstate(void); # define up_dumpstate() #endif -/* Defined in up_allocateheap.c */ +/* Common MIPS32 functions defined in arch/mips/src/MIPS32 */ +/* IRQs */ + +extern uint32_t *up_doirq(int irq, uint32_t *regs); + +/* Signals */ + +extern void up_sigdeliver(void); + +/* Chip-specific functions **************************************************/ +/* Chip specific functions defined in arch/mips/src/ */ +/* IRQs */ + +extern void up_irqinitialize(void); +extern void up_maskack_irq(int irq); +extern void up_clrpend_irq(int irq); + +/* DMA */ + +#ifdef CONFIG_ARCH_DMA +extern void weak_function up_dmainitialize(void); +#endif + +/* Memory management */ #if CONFIG_MM_REGIONS > 1 void up_addregion(void); @@ -191,8 +207,9 @@ void up_addregion(void); # define up_addregion() #endif -/* Defined in up_serial.c */ +/* Serial output */ +extern void up_lowputc(char ch); #if CONFIG_NFILE_DESCRIPTORS > 0 extern void up_earlyserialinit(void); extern void up_serialinit(void); @@ -201,44 +218,11 @@ extern void up_serialinit(void); # define up_serialinit() #endif -/* Defined in drivers/lowconsole.c */ - -#ifdef CONFIG_DEV_LOWCONSOLE -extern void lowconsole_init(void); -#else -# define lowconsole_init() -#endif - -/* Defined in up_watchdog.c */ - -extern void up_wdtinit(void); - -/* Defined in up_timerisr.c */ +/* System timer */ extern void up_timerinit(void); -/* Defined in up_irq.c */ - -extern void up_maskack_irq(int irq); -extern void up_clrpend_irq(int irq); - -/* Defined in board/up_leds.c */ - -#ifdef CONFIG_ARCH_LEDS -extern void up_ledinit(void); -extern void up_ledon(int led); -extern void up_ledoff(int led); -#else -# define up_ledinit() -# define up_ledon(led) -# define up_ledoff(led) -#endif - -/* Defined in board/up_network.c for board-specific ethernet implementations, - * or chip/xyx_ethernet.c for chip-specific ethernet implementations, or - * common/up_etherstub.c for a cornercase where the network is enable yet - * there is no ethernet driver to be initialized. - */ +/* Network */ #ifdef CONFIG_NET extern void up_netinitialize(void); @@ -246,6 +230,8 @@ extern void up_netinitialize(void); # define up_netinitialize() #endif +/* USB */ + #ifdef CONFIG_USBDEV extern void up_usbinitialize(void); extern void up_usbuninitialize(void); @@ -254,6 +240,19 @@ extern void up_usbuninitialize(void); # define up_usbuninitialize() #endif -#endif /* __ASSEMBLY__ */ +/* Board-specific functions *************************************************/ +/* Board specific functions defined in config//src */ +/* LEDs */ + +#ifdef CONFIG_ARCH_LEDS +extern void up_ledon(int led); +extern void up_ledoff(int led); +#else +# define up_ledinit() +# define up_ledon(led) +# define up_ledoff(led) +#endif + +#endif /* __ASSEMBLY__ */ #endif /* __ARCH_MIPS_SRC_COMMON_UP_INTERNAL_H */ 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 - * - * 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 "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 - * - * 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 "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 diff --git a/nuttx/arch/mips/src/pic32mx/Make.defs b/nuttx/arch/mips/src/pic32mx/Make.defs index 7555e9aaf..4cfcc8d3a 100755 --- a/nuttx/arch/mips/src/pic32mx/Make.defs +++ b/nuttx/arch/mips/src/pic32mx/Make.defs @@ -39,7 +39,7 @@ HEAD_ASRC = pic32mx-head.S # Common MIPS files -CMN_ASRCS = up_syscall0.S up_inthandler.S up_bevhandler.S +CMN_ASRCS = up_syscall0.S CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_createstack.c up_doirq.c up_exit.c up_idle.c up_initialize.c \ up_initialstate.c up_interruptcontext.c up_irq.c up_lowputs.c \ @@ -61,7 +61,8 @@ endif # Required PIC32MX files CHIP_ASRCS = -CHIP_CSRCS = pic32mx-irq.c pic32mx-timerisr.c +CHIP_CSRCS = pic32mx-irq.c pic32mx-clockconfig.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/excptmacros.h b/nuttx/arch/mips/src/pic32mx/excptmacros.h index fadc4dd80..1532e2f15 100755 --- a/nuttx/arch/mips/src/pic32mx/excptmacros.h +++ b/nuttx/arch/mips/src/pic32mx/excptmacros.h @@ -56,7 +56,7 @@ ********************************************************************************************/ #if CONFIG_ARCH_INTERRUPTSTACK > 3 - .global g_stackbase + .global g_intstackbase .global g_nestlevel #endif @@ -255,9 +255,9 @@ /* Restore the floating point register state */ - lw k0, REG_MTLO(k1) + lw k0, REG_MFLO(k1) mtlo k0 - lw k0, REG_MTHI(k1) + lw k0, REG_MFHI(k1) mthi k0 /* Restore general purpose registers */ @@ -368,7 +368,8 @@ * stack first. */ - la \tmp3, g_intstack + la \tmp3, g_intstackbase + lw \tmp, (\tmp3) sw sp, (\tmp3) move sp, \tmp3 1: diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c b/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c new file mode 100644 index 000000000..342dd4bf0 --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c @@ -0,0 +1,92 @@ +/************************************************************************** + * arch/mips/src/pic32mx/pic32mx-clockconfig.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 "up_arch.h" +#include "up_internal.h" + +#include "pic32mx-config.h" +#include "pic32mx-internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: pic32mx_clockconfig + * + * Description: + * Called to initialize the PIC32MX clocking using the settings in board.h. + * + **************************************************************************/ + +void pic32mx_clockconfig(void) +{ +# warning "Missing logic" +} + + + diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-config.h b/nuttx/arch/mips/src/pic32mx/pic32mx-config.h new file mode 100755 index 000000000..24838548e --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-config.h @@ -0,0 +1,103 @@ +/************************************************************************************ + * arch/mips/src/pic32mx/pic32mx-config.h + * + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_MIPS_SRC_LPC17XX_LPC17_PIC32_H +#define __ARCH_MIPS_SRC_LPC17XX_LPC17_PIC32_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" +#include "pic32mx-memorymap.h" +#include "pic32mx-uart.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration *********************************************************************/ +/* Don't enable UARTs not supported by the chip. */ + +#if CHIP_NEUARTS < 1 +# undef CONFIG_PIC32MX_UART1 +# undef CONFIG_PIC32MX_UART2 +#endif +#if CHIP_NEUARTS < 2 +# undef CONFIG_PIC32MX_UART2 +#endif + +/* Are any UARTs enabled? */ + +#undef HAVE_UART_DEVICE +#if defined(CONFIG_PIC32MX_UART1) || defined(CONFIG_LPC17_UART1) +# define HAVE_UART_DEVICE 1 +#endif + +/* Is there a serial console? There should be at most one defined. It + * could be on any UARTn, n=0,1 + */ + +#if defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_PIC32MX_UART1) +# undef CONFIG_UART2_SERIAL_CONSOLE +# define HAVE_SERIAL_CONSOLE 1 +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LPC17_UART2) +# undef CONFIG_UART1_SERIAL_CONSOLE +# define HAVE_SERIAL_CONSOLE 1 +#else +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# undef HAVE_SERIAL_CONSOLE +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_MIPS_SRC_LPC17XX_LPC17_PIC32_H */ diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S index e474d57e7..e52e2549f 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S @@ -40,9 +40,10 @@ #include #include -#include #include +#include "excptmacros.h" + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -71,30 +72,61 @@ * 4) Uninitialized data (.bss): * Start: _sbss * End(+1): _ebss + * + * The following are placed outside of the "normal" memory segments -- mostly + * so that they do not have to be cleared on power up. + * * 5) Idle thread stack: * Start: _ebss * End(+1): _ebss+CONFIG_IDLETHREAD_STACKSIZE - * 6) Heap Range + * 6) Optional interrupt stack * Start: _ebss+CONFIG_IDLETHREAD_STACKSIZE + * End(+1): _ebss+CONFIG_IDLETHREAD_STACKSIZE+(CONFIG_ARCH_INTERRUPTSTACK & ~3) + * 6a) Heap (without interupt stack) + * Start: _ebss+CONFIG_IDLETHREAD_STACKSIZE + * End(+1): to the end of memory + * 6b) Heap (with interupt stack) + * Start: _ebss+CONFIG_IDLETHREAD_STACKSIZE+(CONFIG_ARCH_INTERRUPTSTACK & ~3) * End(+1): to the end of memory */ -#define PIC32MX_STACK_BASE _ebss -#define PIC32MX_STACK_TOP _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 -#define PIC32MX_HEAP_BASE _ebss+CONFIG_IDLETHREAD_STACKSIZE +#define PIC32MX_STACK_BASE _ebss +#define PIC32MX_STACK_TOP _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 +# define PIC32MX_INTSTACK_BASE PIC32MX_STACK_TOP +# define PIC32MX_INTSTACK_SIZE (CONFIG_ARCH_INTERRUPTSTACK & ~3) +# define PIC32MX_INTSTACK_TOP PIC32MX_STACK_TOP+PIC32MX_INTSTACK_SIZE +# define PIC32MX_HEAP_BASE PIC32MX_INTSTACK_TOP +#else +# define PIC32MX_HEAP_BASE PIC32MX_STACK_TOP +#endif /**************************************************************************** * Global Symbols ****************************************************************************/ .file "pic32mx-head.S" + + /* Exported symbols */ + + .globl __reset .global __start .global halt +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + .global g_intstackbase + .global g_nestlevel +#endif + .global g_heapbase + + /* Imported symbols */ - .global nmi_handler - .global bev_handler - .global int_handler .global os_start + .global up_dobev + .global up_decodeirq +#ifdef CONFIG_PIC32MX_NMIHANDLER + .global up_donmi +#endif /**************************************************************************** * Name: __reset @@ -112,7 +144,6 @@ * ****************************************************************************/ - .globl __reset .section .reset, "ax", @progbits .set noreorder .ent __reset @@ -122,6 +153,52 @@ __reset: nop .end __reset +/**************************************************************************** + * 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: _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: __start * @@ -148,17 +225,19 @@ __start: * over to the NMI handler. */ +#ifdef CONFIG_PIC32MX_NMIHANDLER mfc0 k0, $12 /* Load CP0 status register */ ext k0, k0, 19, 1 /* Extract NMI bit */ beqz k0, .Lnotnmi nop - la k0, nmi_handler + la k0, _nmi_handler jr k0 nop /* This is not an NMI */ .Lnotnmi: +#endif /* Initialize the stack pointer */ @@ -331,13 +410,79 @@ __start: * necessary */ - and a0, a0, 0 - and a1, a1, 0 la t0, __start_nuttx jr t0 nop .end __start +/**************************************************************************** + * Name: _bev_handler + * + * Description: + * BEV exception handler. Calls up_dobev() + * + ****************************************************************************/ + + .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 + +/**************************************************************************** + * Name: _int_handler + * + * Description: + * Interrupt exception handler. Calls up_decodeirq() + * + ****************************************************************************/ + + .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 + +/**************************************************************************** + * Name: _nmi_handler + * + * Description: + * NMI exception handler. Calls up_donmi + * + ****************************************************************************/ + +#ifdef CONFIG_PIC32MX_NMIHANDLER + .section .nmi_handler, "ax", @progbits + .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) */ + 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() */ + .end _nmi_handler +#endif + /**************************************************************************** * Name: __start_nuttx * @@ -356,19 +501,14 @@ __start: __start_nuttx: /* Perform low level initialization */ - jal up_lowinit + la t0, up_lowinit + jalr t0, ra nop - /* Perform early serial initialization */ - -#ifdef CONFIG_USE_EARLYSERIALINIT - jal up_earlyserialinit - nop -#endif - /* Call os_start */ - jal os_start + la t0, os_start + jalr t0, ra nop /* Just in case main returns, go into infinite loop */ @@ -379,15 +519,41 @@ halt: nop .end __start_nuttx - /* This global variable is unsigned int g_heapbase and is exported - * here only because of its coupling to idle thread stack. - */ +/**************************************************************************** + * Global Data + ****************************************************************************/ + +/* Interrupt stack variables */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + +/* g_instackbase is a pointer to the final, aligned word of the interrupt + * stack. + */ + + .sdata + .type g_intstackbase, object +g_intstackbase: + .long PIC32MX_INTSTACK_TOP-4 + .size g_intstackbase, .-g_intstackbase + +/* g_nextlevel is the exception nesting level... the interrupt stack is not + * available to nested exceptions. + */ + + .sbss + .type g_nestlevel, object +g_nestlevel: + .skip 4 +#endif + +/* This global variable is unsigned int g_heapbase and is exported here only + * because of its coupling to idle thread stack. + */ .sdata - .align 4 - .globl g_heapbase .type g_heapbase, object g_heapbase: - .long _ebss+CONFIG_IDLETHREAD_STACKSIZE + .long PIC32MX_HEAP_BASE .size g_heapbase, .-g_heapbase diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h index 7c40bff8d..da6e8b1f5 100755 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h @@ -49,6 +49,7 @@ #include "up_internal.h" #include "chip.h" +#include "pic32mx-config.h" /************************************************************************************ * Definitions @@ -122,9 +123,7 @@ extern "C" { * Name: pic32mx_clockconfig * * Description: - * Called to initialize the PIC32MX. This does whatever setup is needed to put the - * MCU in a usable state. This includes the initialization of clocking using the - * settings in board.h. + * Called to initialize the PIC32MX clocking using the settings in board.h. * ************************************************************************************/ @@ -134,13 +133,38 @@ EXTERN void pic32mx_clockconfig(void); * Name: pic32mx_lowsetup * * Description: - * Called at the very beginning of _start. Performs low level initialization - * including setup of the console UART. This UART done early so that the serial - * console is available for debugging very early in the boot sequence. + * 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. * ************************************************************************************/ -EXTERN void pic32mx_lowsetup(void); +EXTERN void pic32mx_consoleinit(void); + +/****************************************************************************** + * Name: pic32mx_uartreset + * + * Description: + * Reset a UART. + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +EXTERN void pic32mx_uartreset(uintptr_t uart_base); +#endif + +/****************************************************************************** + * Name: pic32mx_uartconfigure + * + * Description: + * Configure a UART as a RS-232 UART. + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +EXTERN void pic32mx_uartconfigure(uintptr_t uart_base, uint32_t baud, + unsigned int parity, unsigned int nbits, + bool stop2); +#endif /************************************************************************************ * Name: pic32mx_gpioirqinitialize @@ -156,6 +180,28 @@ EXTERN void pic32mx_gpioirqinitialize(void); # define pic32mx_gpioirqinitialize() #endif +/************************************************************************************ + * Name: pic32mx_boardinitialize + * + * Description: + * This function must be provided by the board-specific logic in the directory + * configs//up_boot.c. + * + ************************************************************************************/ + +EXTERN void pic32mx_boardinitialize(void); + +/************************************************************************************ + * Name: up_decodeirq + * + * Description: + * Called from assembly language logic when and interrrupt exception occurs. This + * function decodes and dispatches the interrupt. + * + ************************************************************************************/ + +EXTERN uint32_t *up_decodeirq(uint32_t *regs); + /************************************************************************************ * Name: pic32mx_configgpio * diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-lowconsole.c b/nuttx/arch/mips/src/pic32mx/pic32mx-lowconsole.c new file mode 100644 index 000000000..70d63ee4c --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-lowconsole.c @@ -0,0 +1,204 @@ +/****************************************************************************** + * arch/mips/src/pic32mx/pic32mx-lowconsole.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 "up_arch.h" +#include "up_internal.h" + +#include "pic32mx-config.h" +#include "pic32mx-internal.h" + +/****************************************************************************** + * Private Definitions + ******************************************************************************/ + +/* Select UART parameters for the selected console */ + +#if defined(CONFIG_UART1_SERIAL_CONSOLE) +# define AVR32_CONSOLE_BASE PIC32MX_UART1_K1BASE +# define AVR32_CONSOLE_BAUD CONFIG_UART1_BAUD +# define AVR32_CONSOLE_BITS CONFIG_UART1_BITS +# define AVR32_CONSOLE_PARITY CONFIG_UART1_PARITY +# define AVR32_CONSOLE_2STOP CONFIG_UART1_2STOP +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# define AVR32_CONSOLE_BASE PIC32MX_UART2_K1BASE +# define AVR32_CONSOLE_BAUD CONFIG_UART2_BAUD +# define AVR32_CONSOLE_BITS CONFIG_UART2_BITS +# define AVR32_CONSOLE_PARITY CONFIG_UART2_PARITY +# define AVR32_CONSOLE_2STOP CONFIG_UART2_2STOP +#else +# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting" +#endif + +/****************************************************************************** + * Private Types + ******************************************************************************/ + +/****************************************************************************** + * Private Function Prototypes + ******************************************************************************/ + +/****************************************************************************** + * Global Variables + ******************************************************************************/ + +/****************************************************************************** + * Private Variables + ******************************************************************************/ + +/****************************************************************************** + * Private Functions + ******************************************************************************/ + +/****************************************************************************** + * Name: pic32mx_uartputreg + * + * Description: + * Write a value to a UART register + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +static inline void pic32mx_uartputreg(uintptr_t uart_base, unsigned int offset, + uint32_t value) +{ + putreg32(value, uart_base + offset); +} +#endif + +/****************************************************************************** + * Name: pic32mx_uartgetreg + * + * Description: + * Get a value from a UART register + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +static inline uint32_t pic32mx_uartgetreg(uintptr_t uart_base, + unsigned int offset) +{ + return getreg32(uart_base + offset); +} +#endif + +/****************************************************************************** + * Name: pic32mx_uartsetbaud + * + * Description: + * Configure the UART baud rate. + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +static void pic32mx_uartsetbaud(uintptr_t uart_base, uint32_t baudrate) +{ +#warning "Missing logic" +} +#endif + +/****************************************************************************** + * Public Functions + ******************************************************************************/ + +/****************************************************************************** + * Name: pic32mx_uartreset + * + * Description: + * Reset a UART. + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void pic32mx_uartreset(uintptr_t uart_base) +{ +#warning "Missing logic" +} +#endif + +/****************************************************************************** + * Name: pic32mx_uartconfigure + * + * Description: + * Configure a UART as a RS-232 UART. + * + ******************************************************************************/ + +#ifdef HAVE_UART_DEVICE +void pic32mx_uartconfigure(uintptr_t uart_base, uint32_t baud, + unsigned int parity, unsigned int nbits, bool stop2) +{ +} +#endif + +/****************************************************************************** + * Name: pic32mx_consoleinit + * + * Description: + * Initialize a console for debug output. This function is called very + * early in the intialization sequence to configure the serial console uart + * (only). + * + ******************************************************************************/ + +void pic32mx_consoleinit(void) +{ +#warning "Missing logic" +} + +/****************************************************************************** + * Name: up_lowputc + * + * Description: + * Output one byte on the serial console + * + ******************************************************************************/ + +void up_lowputc(char ch) +{ +#warning "Missing logic" +} + diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c new file mode 100644 index 000000000..cecaf4146 --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c @@ -0,0 +1,106 @@ +/************************************************************************** + * arch/mips/src/pic32/pic32mx-lowinit.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 "up_internal.h" +#include "pic32mx-internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_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. + * + **************************************************************************/ + +void up_lowinit(void) +{ + /* Initialize MCU clocking */ + + pic32mx_clockconfig(); + + /* Initialize a console (probably a serial console) */ + + pic32mx_consoleinit(); + + /* Perform early serial initialization (so that we will have debug output + * available as soon as possible). + */ + +#ifdef CONFIG_USE_EARLYSERIALINIT + up_earlyserialinit(); +#endif + + /* Perform board-level initialization */ + + pic32mx_boardinitialize(); +} + + diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c new file mode 100644 index 000000000..a82a226dc --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c @@ -0,0 +1,766 @@ +/**************************************************************************** + * arch/mips/src/pic32mx/pic32mx-serial.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 +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" +#include "os_internal.h" + +#include "pic32mx-config.h" +#include "chip.h" +#include "pic32mx-uart.h" +#include "pic32mx-internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Some sanity checks *******************************************************/ + +/* Is there at least one UART enabled and configured as a RS-232 device? */ + +#ifndef HAVE_UART_DEVICE +# warning "No UARTs enabled" +#endif + +/* If we are not using the serial driver for the console, then we still must + * provide some minimal implementation of up_putc. + */ + +#ifdef CONFIG_USE_SERIALDRIVER + +/* Which UART with be tty0/console and which tty1? The console will always + * be ttyS0. If there is no console then will use the lowest numbered UART. + */ + +#ifdef HAVE_SERIAL_CONSOLE +# if defined(CONFIG_UART1_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart0port /* UART1 is console */ +# define TTYS0_DEV g_uart0port /* UART1 is ttyS0 */ +# ifdef CONFIG_PIC32MX_UART2 +# define TTYS1_DEV g_uart1port /* UART2 is ttyS1 */ +# else +# undef TTYS1_DEV /* No ttyS1 */ +# endif +# elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# define CONSOLE_DEV g_uart1port /* UART2 is console */ +# define TTYS0_DEV g_uart1port /* UART2 is ttyS0 */ +# undef TTYS1_DEV /* No ttyS1 */ +# else +# error "I'm confused... Do we have a serial console or not?" +# endif +#else +# undef CONSOLE_DEV /* No console */ +# undef CONFIG_UART1_SERIAL_CONSOLE +# undef CONFIG_UART2_SERIAL_CONSOLE +# if defined(CONFIG_PIC32MX_UART1) +# define TTYS0_DEV g_uart0port /* UART1 is ttyS0 */ +# ifdef CONFIG_PIC32MX_UART2 +# define TTYS1_DEV g_uart1port /* UART2 is ttyS1 */ +# else +# undef TTYS1_DEV /* No ttyS1 */ +# endif +# elif defined(CONFIG_PIC32MX_UART2) +# define TTYS0_DEV g_uart1port /* UART2 is ttyS0 */ +# undef TTYS1_DEV /* No ttyS1 */ +# else +# undef TTYS0_DEV +# undef TTYS0_DEV +# endif +#endif + +/* These values describe the set of enabled interrupts */ + +#define IE_ERROR (1 << 0) +#define IE_RX (1 << 1) +#define IE_TX (1 << 2) + +#define ERROR_ENABLED(im) (((im) & IE_ERROR) != 0) +#define RX_ENABLED(im) (((im) & IE_RX) != 0) +#define TX_ENABLED(im) (((im) & IE_TX) != 0) + +#define ENABLE_ERROR(im) do { (im) |= IE_ERROR; } while (0) +#define ENABLE_RX(im) do { (im) |= IE_RX; } while (0) +#define ENABLE_TX(im) do { (im) |= IE_TX; } while (0) + +#define DISABLE_ERROR(im) do { (im) &= ~IE_ERROR; } while (0) +#define DISABLE_RX(im) do { (im) &= ~IE_RX; } while (0) +#define DISABLE_TX(im) do { (im) &= ~IE_TX; } while (0) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct up_dev_s +{ + uintptr_t uartbase; /* Base address of UART registers */ + uint32_t baud; /* Configured baud */ + uint8_t irq; /* IRQ associated with this UART (for attachment) */ + uint8_t irqe; /* Error IRQ associated with this UART (for enable) */ + uint8_t irqrx; /* RX IRQ associated with this UART (for enable) */ + uint8_t irqtx; /* RX IRQ associated with this UART (for enable) */ + uint8_t ie; /* Interrupts enabled */ + uint8_t parity; /* 0=none, 1=odd, 2=even */ + uint8_t bits; /* Number of bits (5, 6, 7 or 8) */ + bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev); +static void up_shutdown(struct uart_dev_s *dev); +static int up_attach(struct uart_dev_s *dev); +static void up_detach(struct uart_dev_s *dev); +static int up_interrupt(int irq, void *context); +static int up_ioctl(struct file *filep, int cmd, unsigned long arg); +static int up_receive(struct uart_dev_s *dev, uint32_t *status); +static void up_rxint(struct uart_dev_s *dev, bool enable); +static bool up_rxavailable(struct uart_dev_s *dev); +static void up_send(struct uart_dev_s *dev, int ch); +static void up_txint(struct uart_dev_s *dev, bool enable); +static bool up_txready(struct uart_dev_s *dev); + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +struct uart_ops_s g_uart_ops = +{ + .setup = up_setup, + .shutdown = up_shutdown, + .attach = up_attach, + .detach = up_detach, + .ioctl = up_ioctl, + .receive = up_receive, + .rxint = up_rxint, + .rxavailable = up_rxavailable, + .send = up_send, + .txint = up_txint, + .txready = up_txready, + .txempty = up_txready, +}; + +/* I/O buffers */ + +#ifdef CONFIG_PIC32MX_UART1 +static char g_uart1rxbuffer[CONFIG_UART2_RXBUFSIZE]; +static char g_uart1txbuffer[CONFIG_UART2_TXBUFSIZE]; +#endif +#ifdef CONFIG_PIC32MX_UART2 +static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE]; +static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE]; +#endif + +/* This describes the state of the AVR32 UART1 port. */ + +#ifdef CONFIG_PIC32MX_UART1 +static struct up_dev_s g_uart1priv = +{ + .uartbase = PIC32MX_UART1_K1BASE, + .baud = CONFIG_UART2_BAUD, + .irq = PIC32MX_IRQ_U1, + .irqe = PIC32MX_IRQSRC_U1E, + .irqrx = PIC32MX_IRQSRC_U1RX, + .irqtx = PIC32MX_IRQSRC_U1TX, + .parity = CONFIG_UART2_PARITY, + .bits = CONFIG_UART2_BITS, + .stopbits2 = CONFIG_UART2_2STOP, +}; + +static uart_dev_t g_uart1port = +{ + .recv = + { + .size = CONFIG_UART2_RXBUFSIZE, + .buffer = g_uart1rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART2_TXBUFSIZE, + .buffer = g_uart1txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart1priv, +}; +#endif + +/* This describes the state of the AVR32 UART2 port. */ + +#ifdef CONFIG_PIC32MX_UART1 +static struct up_dev_s g_uart2priv = +{ + .uartbase = PIC32MX_UART2_K1BASE, + .baud = CONFIG_UART2_BAUD, + .irq = PIC32MX_IRQ_U2, + .irqe = PIC32MX_IRQSRC_U2E, + .irqrx = PIC32MX_IRQSRC_U2RX, + .irqtx = PIC32MX_IRQSRC_U2TX, + .parity = CONFIG_UART2_PARITY, + .bits = CONFIG_UART2_BITS, + .stopbits2 = CONFIG_UART2_2STOP, +}; + +static uart_dev_t g_uart2port = +{ + .recv = + { + .size = CONFIG_UART2_RXBUFSIZE, + .buffer = g_uart2rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART2_TXBUFSIZE, + .buffer = g_uart2txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart2priv, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_serialin + ****************************************************************************/ + +static inline uint32_t up_serialin(struct up_dev_s *priv, int offset) +{ + return getreg32(priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_serialout + ****************************************************************************/ + +static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t value) +{ + putreg32(value, priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_restoreuartint + ****************************************************************************/ + +static void up_restoreuartint(struct up_dev_s *priv, uint8_t im) +{ + /* Re-enable interrupts as for each "1" bit in imr */ + +#warning "Missing logic" +} + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *imr) +{ +#warning "Missing logic" +} + +/**************************************************************************** + * Name: up_setup + * + * Description: + * Configure the UART baud, bits, parity, etc. This method is called the + * first time that the serial port is opened. + * + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev) +{ +#ifndef CONFIG_SUPPRESS_UART_CONFIG + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + + /* Configure the UART as an RS-232 UART */ + + uart_configure(priv->uartbase, priv->baud, priv->parity, + priv->bits, priv->stopbits2); +#endif + + return OK; +} + +/**************************************************************************** + * Name: up_shutdown + * + * Description: + * Disable the UART. This method is called when the serial + * port is closed + * + ****************************************************************************/ + +static void up_shutdown(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + + /* Reset, disable interrupts, and disable Rx and Tx */ + + uart_reset(priv->uartbase); +} + +/**************************************************************************** + * Name: up_attach + * + * Description: + * Configure the UART to operation in interrupt driven mode. This method is + * called when the serial port is opened. Normally, this is just after the + * the setup() method is called, however, the serial console may operate in + * a non-interrupt driven mode during the boot phase. + * + * RX and TX interrupts are not enabled when by the attach method (unless the + * hardware supports multiple levels of interrupt enabling). The RX and TX + * interrupts are not enabled until the txint() and rxint() methods are called. + * + ****************************************************************************/ + +static int up_attach(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + + /* Attach the IRQ */ + + return irq_attach(priv->irq, up_interrupt); +} + +/**************************************************************************** + * Name: up_detach + * + * Description: + * Detach UART interrupts. This method is called when the serial port is + * closed normally just before the shutdown method is called. The exception + * is the serial console which is never shutdown. + * + ****************************************************************************/ + +static void up_detach(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + up_serialout(priv, AVR32_UART_IDR_OFFSET, 0xffffffff); + irq_detach(priv->irq); +} + +/**************************************************************************** + * Name: up_interrupt + * + * Description: + * This is the UART interrupt handler. It will be invoked when an + * interrupt received on the 'irq' It should call uart_transmitchars or + * uart_receivechar to perform the appropriate data transfers. The + * interrupt handling logic must be able to map the 'irq' number into the + * approprite uart_dev_s structure in order to call these functions. + * + ****************************************************************************/ + +static int up_interrupt(int irq, void *context) +{ + struct uart_dev_s *dev = NULL; + struct up_dev_s *priv; + int passes; + bool handled; + +#ifdef CONFIG_PIC32MX_UART1 + if (g_uart1priv.irq == irq) + { + dev = &g_uart1port; + } + else +#endif +#ifdef CONFIG_PIC32MX_UART2 + if (g_uart2priv.irq == irq) + { + dev = &g_uart2port; + } + else +#endif + { + PANIC(OSERR_INTERNAL); + } + priv = (struct up_dev_s*)dev->priv; + DEBUGASSERT(priv); + + /* Loop until there are no characters to be transferred or, + * until we have been looping for a long time. + */ + + handled = true; + for (passes = 0; passes < 256 && handled; passes++) + { + handled = false; + + /* Handle incoming, receive bytes (with or without timeout) */ + +#warning "Missing logic" + { + /* Received data ready... process incoming bytes */ + + uart_recvchars(dev); + handled = true; + } + + /* Handle outgoing, transmit bytes */ + +#warning "Missing logic" + { + /* Transmit data regiser empty ... process outgoing bytes */ + + uart_xmitchars(dev); + handled = true; + } + } + return OK; +} + +/**************************************************************************** + * Name: up_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int up_ioctl(struct file *filep, int cmd, unsigned long arg) +{ +#if 0 /* Reserved for future growth */ + struct inode *inode; + struct uart_dev_s *dev; + struct up_dev_s *priv; + int ret = OK; + + DEBUGASSERT(filep, filep->f_inode); + inode = filep->f_inode; + dev = inode->i_private; + + DEBUGASSERT(dev, dev->priv) + priv = (struct up_dev_s*)dev->priv; + + switch (cmd) + { + case xxx: /* Add commands here */ + break; + + default: + ret = -ENOTTY; + break; + } + + return ret; +#else + return -ENOTTY; +#endif +} + +/**************************************************************************** + * Name: up_receive + * + * Description: + * Called (usually) from the interrupt level to receive one + * character from the UART. Error bits associated with the + * receipt are provided in the return 'status'. + * + ****************************************************************************/ + +static int up_receive(struct uart_dev_s *dev, uint32_t *status) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + + /* Get the Rx byte */ + +#warning "Missing logic" + + /* Return status information */ + + + /* Then return the actual received byte */ + + return 0; +} + +/**************************************************************************** + * Name: up_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +static void up_rxint(struct uart_dev_s *dev, bool enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + + if (enable) + { + /* Receive an interrupt when their is anything in the Rx data register (or an Rx + * timeout occurs). + */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS +# ifdef CONFIG_UART_ERRINTS +#warning "Missing logic" +# else +#warning "Missing logic" +# endif +#endif + } + else + { +#warning "Missing logic" + } +} + +/**************************************************************************** + * Name: up_rxavailable + * + * Description: + * Return true if the receive register is not empty + * + ****************************************************************************/ + +static bool up_rxavailable(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + +#warning "Missing logic" + return false; +} + +/**************************************************************************** + * Name: up_send + * + * Description: + * This method will send one byte on the UART. + * + ****************************************************************************/ + +static void up_send(struct uart_dev_s *dev, int ch) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; +#warning "Missing logic" +} + +/**************************************************************************** + * Name: up_txint + * + * Description: + * Call to enable or disable TX interrupts + * + ****************************************************************************/ + +static void up_txint(struct uart_dev_s *dev, bool enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + irqstate_t flags; + + flags = irqsave(); + if (enable) + { + /* Enable the TX interrupt */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS +#warning "Missing logic" + + /* Fake a TX interrupt here by just calling uart_xmitchars() with + * interrupts disabled (note this may recurse). + */ + + uart_xmitchars(dev); +#endif + } + else + { + /* Disable the TX interrupt */ + +#warning "Missing logic" + } + irqrestore(flags); +} + +/**************************************************************************** + * Name: up_txready + * + * Description: + * Return true if the tranmsit data register is empty + * + ****************************************************************************/ + +static bool up_txready(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + +#warning "Missing logic" + return false; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_earlyserialinit + * + * Description: + * Performs the low level UART initialization early in debug so that the + * serial console will be available during bootup. This must be called + * before up_serialinit. NOTE: This function depends on GPIO pin + * configuration performed in up_consoleinit() and main clock iniialization + * performed in up_clkinitialize(). + * + ****************************************************************************/ + +void up_earlyserialinit(void) +{ + /* Disable all UARTS */ + + up_disableuartint(TTYS0_DEV.priv, NULL); +#ifdef TTYS1_DEV + up_disableuartint(TTYS1_DEV.priv, NULL); +#endif + + /* Configuration whichever one is the console */ + +#ifdef HAVE_SERIAL_CONSOLE + CONSOLE_DEV.isconsole = true; + up_setup(&CONSOLE_DEV); +#endif +} + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Register serial console and serial ports. This assumes + * that up_earlyserialinit was called previously. + * + ****************************************************************************/ + +void up_serialinit(void) +{ + /* Register the console */ + +#ifdef HAVE_SERIAL_CONSOLE + (void)uart_register("/dev/console", &CONSOLE_DEV); +#endif + + /* Register all UARTs */ + + (void)uart_register("/dev/ttyS0", &TTYS0_DEV); +#ifdef TTYS1_DEV + (void)uart_register("/dev/ttyS1", &TTYS1_DEV); +#endif +} + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ +#ifdef HAVE_SERIAL_CONSOLE + struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv; + uint32_t imr; + + up_disableuartint(priv, &imr); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); + up_restoreuartint(priv, imr); +#endif + return ch; +} + +#else /* CONFIG_USE_SERIALDRIVER */ + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ +#ifdef HAVE_SERIAL_CONSOLE + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); +#endif + return ch; +} + +#endif /* CONFIG_USE_SERIALDRIVER */ + -- cgit v1.2.3