diff --git a/nuttx/arch/arm/include/lpc17xx/lpc178x_irq.h b/nuttx/arch/arm/include/lpc17xx/lpc178x_irq.h index 9f7cbf9a77..65738e1c74 100644 --- a/nuttx/arch/arm/include/lpc17xx/lpc178x_irq.h +++ b/nuttx/arch/arm/include/lpc17xx/lpc178x_irq.h @@ -95,7 +95,7 @@ #define LPC17_IRQ_I2C0 (LPC17_IRQ_EXTINT+10) /* I2C0 SI (state change) */ #define LPC17_IRQ_I2C1 (LPC17_IRQ_EXTINT+11) /* I2C1 SI (state change) */ #define LPC17_IRQ_I2C2 (LPC17_IRQ_EXTINT+12) /* I2C2 SI (state change) */ -/* (LPC17_IRQ_EXTINT+13) Unused */ +#define LPC17_IRQ_RESERVED29 (LPC17_IRQ_EXTINT+13) /* Unused */ #define LPC17_IRQ_SSP0 (LPC17_IRQ_EXTINT+14) /* SSP0 Tx FIFO half empty of SSP0 * Rx FIFO half full of SSP0 * Rx Timeout of SSP0 diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_vectors.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_vectors.h new file mode 100644 index 0000000000..d6320bd123 --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_vectors.h @@ -0,0 +1,110 @@ +/******************************************************************************** + * arch/arm/src/lpc17xx/chip/lpc176x_vectors.h + * + * Copyright (C) 2010-2011, 2013 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 + ********************************************************************************/ + +/******************************************************************************** + * Preprocessor Definitions + ********************************************************************************/ +/* This file is included by lpc17_vectors.S. It provides the macro VECTOR that + * supplies each LPC17xx vector in terms of a (lower-case) ISR label and an + * (upper-case) IRQ number as defined in arch/arm/include/lpc17/lpc17xx_irq.h. + * lpc17_vectors.S will defined the VECTOR in different ways in order to generate + * the interrupt vectors and handlers in their final form. + */ + +/* If the common ARMv7-M vector handling is used, then all it needs is the following + * definition that provides the number of supported vectors. + */ + +#ifdef CONFIG_ARMV7M_CMNVECTOR + +/* Reserve 35 interrupt table entries for I/O interrupts. */ + +# define ARMV7M_PERIPHERAL_INTERRUPTS 35 + +#else + +VECTOR(lpc17_wdt, LPC17_IRQ_WDT) /* Vector 16+0: Watchdog timer */ +VECTOR(lpc17_tmr0, LPC17_IRQ_TMR0) /* Vector 16+1: Timer 0 */ +VECTOR(lpc17_tmr1, LPC17_IRQ_TMR1) /* Vector 16+2: Timer 1 */ +VECTOR(lpc17_tmr2, LPC17_IRQ_TMR2) /* Vector 16+3: Timer 2 */ +VECTOR(lpc17_tmr3, LPC17_IRQ_TMR3) /* Vector 16+4: Timer 3 */ +VECTOR(lpc17_uart0, LPC17_IRQ_UART0) /* Vector 16+5: UART 0 */ +VECTOR(lpc17_uart1, LPC17_IRQ_UART1) /* Vector 16+6: UART 1 */ +VECTOR(lpc17_uart2, LPC17_IRQ_UART2) /* Vector 16+7: UART 2 */ +VECTOR(lpc17_uart3, LPC17_IRQ_UART3) /* Vector 16+8: UART 3 */ +VECTOR(lpc17_pwm1, LPC17_IRQ_PWM1) /* Vector 16+9: PWM 1 */ +VECTOR(lpc17_i2c0, LPC17_IRQ_I2C0) /* Vector 16+10: I2C 0 */ +VECTOR(lpc17_i2c1, LPC17_IRQ_I2C1) /* Vector 16+11: I2C 1 */ +VECTOR(lpc17_i2c2, LPC17_IRQ_I2C2) /* Vector 16+12: I2C 2 */ +VECTOR(lpc17_spif, LPC17_IRQ_SPIF) /* Vector 16+13: SPI */ +VECTOR(lpc17_ssp0, LPC17_IRQ_SSP0) /* Vector 16+14: SSP 0 */ +VECTOR(lpc17_ssp1, LPC17_IRQ_SSP1) /* Vector 16+15: SSP 1 */ +VECTOR(lpc17_pll0, LPC17_IRQ_PLL0) /* Vector 16+16: PLL 0 */ +VECTOR(lpc17_rtc, LPC17_IRQ_RTC) /* Vector 16+17: Real time clock */ +VECTOR(lpc17_eint0, LPC17_IRQ_EINT0) /* Vector 16+18: External interrupt 0 */ +VECTOR(lpc17_eint1, LPC17_IRQ_EINT1) /* Vector 16+19: External interrupt 1 */ +VECTOR(lpc17_eint2, LPC17_IRQ_EINT2) /* Vector 16+20: External interrupt 2 */ +VECTOR(lpc17_eint3, LPC17_IRQ_EINT3) /* Vector 16+21: External interrupt 3 */ +VECTOR(lpc17_adc, LPC17_IRQ_ADC) /* Vector 16+22: A/D Converter */ +VECTOR(lpc17_bod, LPC17_IRQ_BOD) /* Vector 16+23: Brown Out detect */ +VECTOR(lpc17_usb, LPC17_IRQ_USB) /* Vector 16+24: USB */ +VECTOR(lpc17_can, LPC17_IRQ_CAN) /* Vector 16+25: CAN */ +VECTOR(lpc17_gpdma, LPC17_IRQ_GPDMA) /* Vector 16+26: GPDMA */ +VECTOR(lpc17_i2s, LPC17_IRQ_I2S) /* Vector 16+27: I2S */ +VECTOR(lpc17_eth, LPC17_IRQ_ETH) /* Vector 16+28: Ethernet */ +VECTOR(lpc17_ritint, LPC17_IRQ_RITINT) /* Vector 16+29: Repetitive Interrupt Timer */ +VECTOR(lpc17_mcpwm, LPC17_IRQ_MCPWM) /* Vector 16+30: Motor Control PWM */ +VECTOR(lpc17_qei, LPC17_IRQ_QEI) /* Vector 16+31: Quadrature Encoder */ +VECTOR(lpc17_pll1, LPC17_IRQ_PLL1) /* Vector 16+32: PLL 1 */ +VECTOR(lpc17_usbact, LPC17_IRQ_USBACT) /* Vector 16+33: USB Activity Interrupt */ +VECTOR(lpc17_canact, LPC17_IRQ_CANACT) /* Vector 16+34: CAN Activity Interrupt */ + +#endif + +/******************************************************************************** + * Public Types + ********************************************************************************/ + +/******************************************************************************** + * Public Data + ********************************************************************************/ + +/******************************************************************************** + * Public Function Prototypes + ********************************************************************************/ diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_vectors.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_vectors.h new file mode 100644 index 0000000000..001cc7690e --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_vectors.h @@ -0,0 +1,117 @@ +/************************************************************************************************ + * arch/arm/src/lpc17xx/chip/lpc178x_vectors.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Rommel Marcelo + * 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 + ********************************************************************************/ + +/********************************************************************************* + * Preprocessor Definitions + ********************************************************************************/ +/* This file is included by lpc17_vectors.S. It provides the macro VECTOR that + * supplies each LPC17xx vector in terms of a (lower-case) ISR label and an + * (upper-case) IRQ number as defined in arch/arm/include/lpc17/lpc17xx_irq.h. + * lpc17_vectors.S will defined the VECTOR in different ways in order to generate + * the interrupt vectors and handlers in their final form. + */ + +/* If the common ARMv7-M vector handling is used, then all it needs is the following + * definition that provides the number of supported vectors. + */ + +#ifdef CONFIG_ARMV7M_CMNVECTOR + +/* Reserve 41 interrupt table entries for I/O interrupts. */ + +# define ARMV7M_PERIPHERAL_INTERRUPTS 41 + +#else + +VECTOR(lpc17_wdt, LPC17_IRQ_WDT) /* Vector 16+0: Watchdog timer */ +VECTOR(lpc17_tmr0, LPC17_IRQ_TMR0) /* Vector 16+1: Timer 0 */ +VECTOR(lpc17_tmr1, LPC17_IRQ_TMR1) /* Vector 16+2: Timer 1 */ +VECTOR(lpc17_tmr2, LPC17_IRQ_TMR2) /* Vector 16+3: Timer 2 */ +VECTOR(lpc17_tmr3, LPC17_IRQ_TMR3) /* Vector 16+4: Timer 3 */ +VECTOR(lpc17_uart0, LPC17_IRQ_UART0) /* Vector 16+5: UART 0 */ +VECTOR(lpc17_uart1, LPC17_IRQ_UART1) /* Vector 16+6: UART 1 */ +VECTOR(lpc17_uart2, LPC17_IRQ_UART2) /* Vector 16+7: UART 2 */ +VECTOR(lpc17_uart3, LPC17_IRQ_UART3) /* Vector 16+8: UART 3 */ +VECTOR(lpc17_pwm1, LPC17_IRQ_PWM1) /* Vector 16+9: PWM 1 */ +VECTOR(lpc17_i2c0, LPC17_IRQ_I2C0) /* Vector 16+10: I2C 0 */ +VECTOR(lpc17_i2c1, LPC17_IRQ_I2C1) /* Vector 16+11: I2C 1 */ +VECTOR(lpc17_i2c2, LPC17_IRQ_I2C2) /* Vector 16+12: I2C 2 */ +UNUSED(LPC17_IRQ_RESERVED29) /* Vector 16+13: Reserved */ +VECTOR(lpc17_ssp0, LPC17_IRQ_SSP0) /* Vector 16+14: SSP 0 */ +VECTOR(lpc17_ssp1, LPC17_IRQ_SSP1) /* Vector 16+15: SSP 1 */ +VECTOR(lpc17_pll0, LPC17_IRQ_PLL0) /* Vector 16+16: PLL 0 */ +VECTOR(lpc17_rtc, LPC17_IRQ_RTC) /* Vector 16+17: Real time clock */ +VECTOR(lpc17_eint0, LPC17_IRQ_EINT0) /* Vector 16+18: External interrupt 0 */ +VECTOR(lpc17_eint1, LPC17_IRQ_EINT1) /* Vector 16+19: External interrupt 1 */ +VECTOR(lpc17_eint2, LPC17_IRQ_EINT2) /* Vector 16+20: External interrupt 2 */ +VECTOR(lpc17_eint3, LPC17_IRQ_EINT3) /* Vector 16+21: External interrupt 3 */ +VECTOR(lpc17_adc, LPC17_IRQ_ADC) /* Vector 16+22: A/D Converter */ +VECTOR(lpc17_bod, LPC17_IRQ_BOD) /* Vector 16+23: Brown Out detect */ +VECTOR(lpc17_usb, LPC17_IRQ_USB) /* Vector 16+24: USB */ +VECTOR(lpc17_can, LPC17_IRQ_CAN) /* Vector 16+25: CAN */ +VECTOR(lpc17_gpdma, LPC17_IRQ_GPDMA) /* Vector 16+26: GPDMA */ +VECTOR(lpc17_i2s, LPC17_IRQ_I2S) /* Vector 16+27: I2S */ +VECTOR(lpc17_eth, LPC17_IRQ_ETH) /* Vector 16+28: Ethernet */ +VECTOR(lpc17_mci, LPC17_IRQ_MCI) /* Vector 16+29: MMC/SD */ +VECTOR(lpc17_mcpwm, LPC17_IRQ_MCPWM) /* Vector 16+30: Motor Control PWM */ +VECTOR(lpc17_qei, LPC17_IRQ_QEI) /* Vector 16+31: Quadrature Encoder */ +VECTOR(lpc17_pll1, LPC17_IRQ_PLL1) /* Vector 16+32: PLL 1 */ +VECTOR(lpc17_usbact, LPC17_IRQ_USBACT) /* Vector 16+33: USB Activity Interrupt */ +VECTOR(lpc17_canact, LPC17_IRQ_CANACT) /* Vector 16+34: CAN Activity Interrupt */ +VECTOR(lpc17_uart4, LPC17_IRQ_UART4) /* Vector 16+35: UART 4 */ +VECTOR(lpc17_ssp2, LPC17_IRQ_SSP2) /* Vector 16+36: SSP 2 */ +VECTOR(lpc17_lcd, LPC17_IRQ_LCD) /* Vector 16+37: LCD */ +VECTOR(lpc17_gpio, LPC17_IRQ_GPIO) /* Vector 16+38: GPIO */ +VECTOR(lpc17_pwm0, LPC17_IRQ_PWM0) /* Vector 16+39: PWM0 */ +VECTOR(lpc17_eeprom, LPC17_IRQ_EEPROM) /* Vector 16+40: EEPROM */ + +#endif + +/******************************************************************************** + * Public Types + ********************************************************************************/ + +/******************************************************************************** + * Public Data + ********************************************************************************/ + +/******************************************************************************** + * Public Function Prototypes + ********************************************************************************/ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S index cdb4bef66c..74e53b4115 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S @@ -2,7 +2,7 @@ * arch/arm/src/lpc17xx/lpc17_vectors.S * arch/arm/src/chip/lpc17_vectors.S * - * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2010-2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -128,41 +128,20 @@ lpc17_vectors: /* External Interrupts */ - .word lpc17_wdt /* Vector 16+0: Watchdog timer */ - .word lpc17_tmr0 /* Vector 16+1: Timer 0 */ - .word lpc17_tmr1 /* Vector 16+2: Timer 1 */ - .word lpc17_tmr2 /* Vector 16+3: Timer 2 */ - .word lpc17_tmr3 /* Vector 16+4: Timer 3 */ - .word lpc17_uart0 /* Vector 16+5: UART 0 */ - .word lpc17_uart1 /* Vector 16+6: UART 1 */ - .word lpc17_uart2 /* Vector 16+7: UART 2 */ - .word lpc17_uart3 /* Vector 16+8: UART 3 */ - .word lpc17_pwm1 /* Vector 16+9: PWM */ - .word lpc17_i2c0 /* Vector 16+10: I2C 0 */ - .word lpc17_i2c1 /* Vector 16+11: I2C 1 */ - .word lpc17_i2c2 /* Vector 16+12: I2C 2 */ - .word lpc17_spif /* Vector 16+13: SPI */ - .word lpc17_ssp0 /* Vector 16+14: SSP 0 */ - .word lpc17_ssp1 /* Vector 16+15: SSP 1 */ - .word lpc17_pll0 /* Vector 16+16: PLL 0 */ - .word lpc17_rtc /* Vector 16+17: Real time clock */ - .word lpc17_eint0 /* Vector 16+18: External interrupt 0 */ - .word lpc17_eint1 /* Vector 16+19: External interrupt 1 */ - .word lpc17_eint2 /* Vector 16+20: External interrupt 2 */ - .word lpc17_eint3 /* Vector 16+21: External interrupt 3 */ - .word lpc17_adc /* Vector 16+22: A/D Converter */ - .word lpc17_bod /* Vector 16+23: Brown Out detect */ - .word lpc17_usb /* Vector 16+24: USB */ - .word lpc17_can /* Vector 16+25: CAN */ - .word lpc17_gpdma /* Vector 16+26: GPDMA */ - .word lpc17_i2s /* Vector 16+27: I2S */ - .word lpc17_eth /* Vector 16+28: Ethernet */ - .word lpc17_ritint /* Vector 16+29: Repetitive Interrupt Timer */ - .word lpc17_mcpwm /* Vector 16+30: Motor Control PWM */ - .word lpc17_qei /* Vector 16+31: Quadrature Encoder */ - .word lpc17_pll1 /* Vector 16+32: PLL 1 */ - .word lpc17_usbact /* Vector 16+33: USB Activity Interrupt */ - .word lpc17_canact /* Vector 16+34: CAN Activity Interrupt */ +#undef VECTOR +#define VECTOR(l,i) .word l + +#undef UNUSED +#define UNUSED(i) .word lpc17_reserved + +#if defined(LPC176x) +# include "chip/lpc176x_vectors.h" +#elif defined(LPC178x) +# include "chip/lpc178x_vectors.h" +#else +# error "Unrecognized LPC17xx family" +#endif + .size lpc17_vectors, .-lpc17_vectors /************************************************************************************************ @@ -184,41 +163,21 @@ handlers: HANDLER lpc17_pendsv, LPC17_IRQ_PENDSV /* Vector 14: Penable system service request */ HANDLER lpc17_systick, LPC17_IRQ_SYSTICK /* Vector 15: System tick */ - HANDLER lpc17_wdt, LPC17_IRQ_WDT /* Vector 16+0: Watchdog timer */ - HANDLER lpc17_tmr0, LPC17_IRQ_TMR0 /* Vector 16+1: Timer 0 */ - HANDLER lpc17_tmr1, LPC17_IRQ_TMR1 /* Vector 16+2: Timer 1 */ - HANDLER lpc17_tmr2, LPC17_IRQ_TMR2 /* Vector 16+3: Timer 2 */ - HANDLER lpc17_tmr3, LPC17_IRQ_TMR3 /* Vector 16+4: Timer 3 */ - HANDLER lpc17_uart0, LPC17_IRQ_UART0 /* Vector 16+5: UART 0 */ - HANDLER lpc17_uart1, LPC17_IRQ_UART1 /* Vector 16+6: UART 1 */ - HANDLER lpc17_uart2, LPC17_IRQ_UART2 /* Vector 16+7: UART 2 */ - HANDLER lpc17_uart3, LPC17_IRQ_UART3 /* Vector 16+8: UART 3 */ - HANDLER lpc17_pwm1, LPC17_IRQ_PWM1 /* Vector 16+9: PWM 1 */ - HANDLER lpc17_i2c0, LPC17_IRQ_I2C0 /* Vector 16+10: I2C 0 */ - HANDLER lpc17_i2c1, LPC17_IRQ_I2C1 /* Vector 16+11: I2C 1 */ - HANDLER lpc17_i2c2, LPC17_IRQ_I2C2 /* Vector 16+12: I2C 2 */ - HANDLER lpc17_spif, LPC17_IRQ_SPIF /* Vector 16+13: SPI */ - HANDLER lpc17_ssp0, LPC17_IRQ_SSP0 /* Vector 16+14: SSP 0 */ - HANDLER lpc17_ssp1, LPC17_IRQ_SSP1 /* Vector 16+15: SSP 1 */ - HANDLER lpc17_pll0, LPC17_IRQ_PLL0 /* Vector 16+16: PLL 0 */ - HANDLER lpc17_rtc, LPC17_IRQ_RTC /* Vector 16+17: Real time clock */ - HANDLER lpc17_eint0, LPC17_IRQ_EINT0 /* Vector 16+18: External interrupt 0 */ - HANDLER lpc17_eint1, LPC17_IRQ_EINT1 /* Vector 16+19: External interrupt 1 */ - HANDLER lpc17_eint2, LPC17_IRQ_EINT2 /* Vector 16+20: External interrupt 2 */ - HANDLER lpc17_eint3, LPC17_IRQ_EINT3 /* Vector 16+21: External interrupt 3 */ - HANDLER lpc17_adc, LPC17_IRQ_ADC /* Vector 16+22: A/D Converter */ - HANDLER lpc17_bod, LPC17_IRQ_BOD /* Vector 16+23: Brown Out detect */ - HANDLER lpc17_usb, LPC17_IRQ_USB /* Vector 16+24: USB */ - HANDLER lpc17_can, LPC17_IRQ_CAN /* Vector 16+25: CAN */ - HANDLER lpc17_gpdma, LPC17_IRQ_GPDMA /* Vector 16+26: GPDMA */ - HANDLER lpc17_i2s, LPC17_IRQ_I2S /* Vector 16+27: I2S */ - HANDLER lpc17_eth, LPC17_IRQ_ETH /* Vector 16+28: Ethernet */ - HANDLER lpc17_ritint, LPC17_IRQ_RITINT /* Vector 16+29: Repetitive Interrupt Timer */ - HANDLER lpc17_mcpwm, LPC17_IRQ_MCPWM /* Vector 16+30: Motor Control PWM */ - HANDLER lpc17_qei, LPC17_IRQ_QEI /* Vector 16+31: Quadrature Encoder */ - HANDLER lpc17_pll1, LPC17_IRQ_PLL1 /* Vector 16+32: PLL 1 */ - HANDLER lpc17_usbact, LPC17_IRQ_USBACT /* Vector 16+33: USB Activity Interrupt */ - HANDLER lpc17_canact, LPC17_IRQ_CANACT /* Vector 16+34: CAN Activity Interrupt */ +/* External Interrupts */ + +#undef VECTOR +#define VECTOR(l,i) HANDLER l, i + +#undef UNUSED +#define UNUSED(i) + +#if defined(LPC176x) +# include "chip/lpc176x_vectors.h" +#elif defined(LPC178x) +# include "chip/lpc178x_vectors.h" +#else +# error "Unrecognized LPC17xx family" +#endif /* Common IRQ handling logic. On entry here, the return stack is on either * the PSP or the MSP and looks like the following: