diff --git a/os/hal/platforms/LPC11Uxx/hal_lld.c b/os/hal/platforms/LPC11Uxx/hal_lld.c new file mode 100644 index 000000000..9b1fac622 --- /dev/null +++ b/os/hal/platforms/LPC11Uxx/hal_lld.c @@ -0,0 +1,124 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, + 2011,2012 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file LPC11Uxx/hal_lld.c + * @brief LPC11Uxx HAL subsystem low level driver source. + * + * @addtogroup HAL + * @{ + */ + +#include "ch.h" +#include "hal.h" + +/** + * @brief Register missing in NXP header file. + */ +#define FLASHCFG (*((volatile uint32_t *)0x4003C010)) + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief Low level HAL driver initialization. + * + * @notapi + */ +void hal_lld_init(void) { + + /* SysTick initialization using the system clock.*/ + nvicSetSystemHandlerPriority(HANDLER_SYSTICK, CORTEX_PRIORITY_SYSTICK); + SysTick->LOAD = LPC_SYSCLK / CH_FREQUENCY - 1; + SysTick->VAL = 0; + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_ENABLE_Msk | + SysTick_CTRL_TICKINT_Msk; +} + +/** + * @brief LPC11Uxx clocks and PLL initialization. + * @note All the involved constants come from the file @p board.h. + * @note This function must be invoked only after the system reset. + * + * @special + */ +void lpc_clock_init(void) { + unsigned i; + + /* Flash wait states setting, the code takes care to not touch TBD bits.*/ + FLASHCFG = (FLASHCFG & ~3) | LPC_FLASHCFG_FLASHTIM; + + /* System oscillator initialization if required.*/ +#if LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_PLLOUT +#if LPC_PLLCLK_SOURCE == SYSPLLCLKSEL_SYSOSC + LPC_SYSCON->SYSOSCCTRL = LPC_SYSOSCCTRL; + LPC_SYSCON->PDRUNCFG &= ~(1 << 5); /* System oscillator ON. */ + for (i = 0; i < 200; i++) + __NOP(); /* Stabilization delay. */ +#endif /* LPC_PLLCLK_SOURCE == SYSPLLCLKSEL_SYSOSC */ + + /* PLL initialization if required.*/ + LPC_SYSCON->SYSPLLCLKSEL = LPC_PLLCLK_SOURCE; + LPC_SYSCON->SYSPLLCLKUEN = 1; /* Really required? */ + LPC_SYSCON->SYSPLLCLKUEN = 0; + LPC_SYSCON->SYSPLLCLKUEN = 1; + LPC_SYSCON->SYSPLLCTRL = LPC_SYSPLLCTRL_MSEL | LPC_SYSPLLCTRL_PSEL; + LPC_SYSCON->PDRUNCFG &= ~(1 << 7); /* System PLL ON. */ + while ((LPC_SYSCON->SYSPLLSTAT & 1) == 0) /* Wait PLL lock. */ + ; +#endif /* LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_PLLOUT */ + + /* Main clock source selection.*/ + LPC_SYSCON->MAINCLKSEL = LPC_MAINCLK_SOURCE; + LPC_SYSCON->MAINCLKUEN = 1; /* Really required? */ + LPC_SYSCON->MAINCLKUEN = 0; + LPC_SYSCON->MAINCLKUEN = 1; + while ((LPC_SYSCON->MAINCLKUEN & 1) == 0) /* Wait switch completion. */ + ; + + /* ABH divider initialization, peripheral clocks are initially disabled, + the various device drivers will handle their own setup except GPIO and + IOCON that are left enabled.*/ + LPC_SYSCON->SYSAHBCLKDIV = LPC_SYSABHCLK_DIV; + LPC_SYSCON->SYSAHBCLKCTRL = 0x0001005F; + + /* Memory remapping, vectors always in ROM.*/ + LPC_SYSCON->SYSMEMREMAP = 2; +} + +/** @} */ diff --git a/os/hal/platforms/LPC11Uxx/hal_lld.h b/os/hal/platforms/LPC11Uxx/hal_lld.h new file mode 100644 index 000000000..a544dfa9a --- /dev/null +++ b/os/hal/platforms/LPC11Uxx/hal_lld.h @@ -0,0 +1,222 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, + 2011,2012 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file LPC11Uxx/hal_lld.h + * @brief HAL subsystem low level driver header template. + * + * @addtogroup HAL + * @{ + */ + +#ifndef _HAL_LLD_H_ +#define _HAL_LLD_H_ + +#include "LPC11Uxx.h" +#include "nvic.h" + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/** + * @brief Defines the support for realtime counters in the HAL. + */ +#define HAL_IMPLEMENTS_COUNTERS FALSE + +/** + * @brief Platform name. + */ +#define PLATFORM_NAME "LPC11Uxx" + +#define IRCOSCCLK 12000000 /**< High speed internal clock. */ +#define WDGOSCCLK 1600000 /**< Watchdog internal clock. */ + +#define SYSPLLCLKSEL_IRCOSC 0 /**< Internal RC oscillator + clock source. */ +#define SYSPLLCLKSEL_SYSOSC 1 /**< System oscillator clock + source. */ + +#define SYSMAINCLKSEL_IRCOSC 0 /**< Clock source is IRC. */ +#define SYSMAINCLKSEL_PLLIN 1 /**< Clock source is PLLIN. */ +#define SYSMAINCLKSEL_WDGOSC 2 /**< Clock source is WDGOSC. */ +#define SYSMAINCLKSEL_PLLOUT 3 /**< Clock source is PLLOUT. */ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @brief System PLL clock source. + */ +#if !defined(LPC_PLLCLK_SOURCE) || defined(__DOXYGEN__) +#define LPC_PLLCLK_SOURCE SYSPLLCLKSEL_SYSOSC +#endif + +/** + * @brief System PLL multiplier. + * @note The value must be in the 1..32 range and the final frequency + * must not exceed the CCO ratings. + */ +#if !defined(LPC_SYSPLL_MUL) || defined(__DOXYGEN__) +#define LPC_SYSPLL_MUL 4 +#endif + +/** + * @brief System PLL divider. + * @note The value must be chosen between (2, 4, 8, 16). + */ +#if !defined(LPC_SYSPLL_DIV) || defined(__DOXYGEN__) +#define LPC_SYSPLL_DIV 4 +#endif + +/** + * @brief System main clock source. + */ +#if !defined(LPC_MAINCLK_SOURCE) || defined(__DOXYGEN__) +#define LPC_MAINCLK_SOURCE SYSMAINCLKSEL_PLLOUT +#endif + +/** + * @brief AHB clock divider. + * @note The value must be chosen between (1...255). + */ +#if !defined(LPC_SYSCLK_DIV) || defined(__DOXYGEN__) +#define LPC_SYSABHCLK_DIV 1 +#endif + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +/** + * @brief Calculated SYSOSCCTRL setting. + */ +#if (SYSOSCCLK < 18000000) || defined(__DOXYGEN__) +#define LPC_SYSOSCCTRL 0 +#else +#define LPC_SYSOSCCTRL 1 +#endif + +/** + * @brief PLL input clock frequency. + */ +#if (LPC_PLLCLK_SOURCE == SYSPLLCLKSEL_SYSOSC) || defined(__DOXYGEN__) +#define LPC_SYSPLLCLKIN SYSOSCCLK +#elif LPC_PLLCLK_SOURCE == SYSPLLCLKSEL_IRCOSC +#define LPC_SYSPLLCLKIN IRCOSCCLK +#else +#error "invalid LPC_PLLCLK_SOURCE clock source specified" +#endif + +/** + * @brief MSEL mask in SYSPLLCTRL register. + */ +#if (LPC_SYSPLL_MUL >= 1) && (LPC_SYSPLL_MUL <= 32) || defined(__DOXYGEN__) +#define LPC_SYSPLLCTRL_MSEL (LPC_SYSPLL_MUL - 1) +#else +#error "LPC_SYSPLL_MUL out of range (1...32)" +#endif + +/** + * @brief PSEL mask in SYSPLLCTRL register. + */ +#if (LPC_SYSPLL_DIV == 2) || defined(__DOXYGEN__) +#define LPC_SYSPLLCTRL_PSEL (0 << 5) +#elif LPC_SYSPLL_DIV == 4 +#define LPC_SYSPLLCTRL_PSEL (1 << 5) +#elif LPC_SYSPLL_DIV == 8 +#define LPC_SYSPLLCTRL_PSEL (2 << 5) +#elif LPC_SYSPLL_DIV == 16 +#define LPC_SYSPLLCTRL_PSEL (3 << 5) +#else +#error "invalid LPC_SYSPLL_DIV value (2,4,8,16)" +#endif + +/** + * @brief CCP frequency. + */ +#define LPC_SYSPLLCCO (LPC_SYSPLLCLKIN * LPC_SYSPLL_MUL * \ + LPC_SYSPLL_DIV) + +#if (LPC_SYSPLLCCO < 156000000) || (LPC_SYSPLLCCO > 320000000) +#error "CCO frequency out of the acceptable range (156...320)" +#endif + +/** + * @brief PLL output clock frequency. + */ +#define LPC_SYSPLLCLKOUT (LPC_SYSPLLCCO / LPC_SYSPLL_DIV) + +#if (LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_IRCOSC) || defined(__DOXYGEN__) +#define LPC_MAINCLK IRCOSCCLK +#elif LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_PLLIN +#define LPC_MAINCLK LPC_SYSPLLCLKIN +#elif LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_WDGOSC +#define LPC_MAINCLK WDGOSCCLK +#elif LPC_MAINCLK_SOURCE == SYSMAINCLKSEL_PLLOUT +#define LPC_MAINCLK LPC_SYSPLLCLKOUT +#else +#error "invalid LPC_MAINCLK_SOURCE clock source specified" +#endif + +/** + * @brief AHB clock. + */ +#define LPC_SYSCLK (LPC_MAINCLK / LPC_SYSABHCLK_DIV) +#if LPC_SYSCLK > 50000000 +#error "AHB clock frequency out of the acceptable range (50MHz max)" +#endif + +/** + * @brief Flash wait states. + */ +#if (LPC_SYSCLK <= 20000000) || defined(__DOXYGEN__) +#define LPC_FLASHCFG_FLASHTIM 0 +#elif LPC_SYSCLK <= 40000000 +#define LPC_FLASHCFG_FLASHTIM 1 +#else +#define LPC_FLASHCFG_FLASHTIM 2 +#endif + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +#ifdef __cplusplus +extern "C" { +#endif + void hal_lld_init(void); + void lpc111x_clock_init(void); +#ifdef __cplusplus +} +#endif + +#endif /* _HAL_LLD_H_ */ + +/** @} */ diff --git a/os/hal/platforms/LPC11Uxx/platform.mk b/os/hal/platforms/LPC11Uxx/platform.mk new file mode 100644 index 000000000..3dc47e897 --- /dev/null +++ b/os/hal/platforms/LPC11Uxx/platform.mk @@ -0,0 +1,7 @@ +# List of all the LPC11Uxx platform files. +PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/LPC11Uxx/hal_lld.c \ + ${CHIBIOS}/os/hal/platforms/LPC11Uxx/pal_lld.c \ + ${CHIBIOS}/os/hal/platforms/LPC11Uxx/serial_lld.c + +# Required include directories +PLATFORMINC = ${CHIBIOS}/os/hal/platforms/LPC11Uxx diff --git a/os/hal/platforms/LPC11Uxx/serial_lld.c b/os/hal/platforms/LPC11Uxx/serial_lld.c new file mode 100644 index 000000000..afe371238 --- /dev/null +++ b/os/hal/platforms/LPC11Uxx/serial_lld.c @@ -0,0 +1,302 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, + 2011,2012 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file LPC11Uxx/serial_lld.c + * @brief LPC11Uxx low level serial driver code. + * + * @addtogroup SERIAL + * @{ + */ + +#include "ch.h" +#include "hal.h" + +#if HAL_USE_SERIAL || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +#if LPC_SERIAL_USE_UART0 || defined(__DOXYGEN__) +/** @brief UART0 serial driver identifier.*/ +SerialDriver SD1; +#endif + +/*===========================================================================*/ +/* Driver local variables. */ +/*===========================================================================*/ + +/** @brief Driver default configuration.*/ +static const SerialConfig default_config = { + SERIAL_DEFAULT_BITRATE, + LCR_WL8 | LCR_STOP1 | LCR_NOPARITY, + FCR_TRIGGER0 +}; + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/** + * @brief UART initialization. + * + * @param[in] sdp communication channel associated to the UART + * @param[in] config the architecture-dependent serial driver configuration + */ +static void uart_init(SerialDriver *sdp, const SerialConfig *config) { + LPC_UART_TypeDef *u = sdp->uart; + + uint32_t div = LPC_SERIAL_UART0_PCLK / (config->sc_speed << 4); + u->LCR = config->sc_lcr | LCR_DLAB; + u->DLL = div; + u->DLM = div >> 8; + u->LCR = config->sc_lcr; + u->FCR = FCR_ENABLE | FCR_RXRESET | FCR_TXRESET | config->sc_fcr; + u->ACR = 0; + u->FDR = 0x10; + u->TER = TER_ENABLE; + u->IER = IER_RBR | IER_STATUS; +} + +/** + * @brief UART de-initialization. + * + * @param[in] u pointer to an UART I/O block + */ +static void uart_deinit(LPC_UART_TypeDef *u) { + + u->LCR = LCR_DLAB; + u->DLL = 1; + u->DLM = 0; + u->LCR = 0; + u->FDR = 0x10; + u->IER = 0; + u->FCR = FCR_RXRESET | FCR_TXRESET; + u->ACR = 0; + u->TER = TER_ENABLE; +} + +/** + * @brief Error handling routine. + * + * @param[in] sdp communication channel associated to the UART + * @param[in] err UART LSR register value + */ +static void set_error(SerialDriver *sdp, IOREG32 err) { + chnflags_t sts = 0; + + if (err & LSR_OVERRUN) + sts |= SD_OVERRUN_ERROR; + if (err & LSR_PARITY) + sts |= SD_PARITY_ERROR; + if (err & LSR_FRAMING) + sts |= SD_FRAMING_ERROR; + if (err & LSR_BREAK) + sts |= SD_BREAK_DETECTED; + chSysLockFromIsr(); + chnAddFlagsI(sdp, sts); + chSysUnlockFromIsr(); +} + +/** + * @brief Common IRQ handler. + * @note Tries hard to clear all the pending interrupt sources, we don't + * want to go through the whole ISR and have another interrupt soon + * after. + * + * @param[in] u pointer to an UART I/O block + * @param[in] sdp communication channel associated to the UART + */ +static void serve_interrupt(SerialDriver *sdp) { + LPC_UART_TypeDef *u = sdp->uart; + + while (TRUE) { + switch (u->IIR & IIR_SRC_MASK) { + case IIR_SRC_NONE: + return; + case IIR_SRC_ERROR: + set_error(sdp, u->LSR); + break; + case IIR_SRC_TIMEOUT: + case IIR_SRC_RX: + chSysLockFromIsr(); + if (chIQIsEmptyI(&sdp->iqueue)) + chnAddFlagsI(sdp, CHN_INPUT_AVAILABLE); + chSysUnlockFromIsr(); + while (u->LSR & LSR_RBR_FULL) { + chSysLockFromIsr(); + if (chIQPutI(&sdp->iqueue, u->RBR) < Q_OK) + chnAddFlagsI(sdp, SD_OVERRUN_ERROR); + chSysUnlockFromIsr(); + } + break; + case IIR_SRC_TX: + { + int i = LPC_SERIAL_FIFO_PRELOAD; + do { + msg_t b; + + chSysLockFromIsr(); + b = chOQGetI(&sdp->oqueue); + chSysUnlockFromIsr(); + if (b < Q_OK) { + u->IER &= ~IER_THRE; + chSysLockFromIsr(); + chnAddFlagsI(sdp, CHN_OUTPUT_EMPTY); + chSysUnlockFromIsr(); + break; + } + u->THR = b; + } while (--i); + } + break; + default: + (void) u->THR; + (void) u->RBR; + } + } +} + +/** + * @brief Attempts a TX FIFO preload. + */ +static void preload(SerialDriver *sdp) { + LPC_UART_TypeDef *u = sdp->uart; + + if (u->LSR & LSR_THRE) { + int i = LPC_SERIAL_FIFO_PRELOAD; + do { + msg_t b = chOQGetI(&sdp->oqueue); + if (b < Q_OK) { + chnAddFlagsI(sdp, CHN_OUTPUT_EMPTY); + return; + } + u->THR = b; + } while (--i); + } + u->IER |= IER_THRE; +} + +/** + * @brief Driver SD1 output notification. + */ +#if LPC_SERIAL_USE_UART0 || defined(__DOXYGEN__) +static void notify1(GenericQueue *qp) { + + (void)qp; + preload(&SD1); +} +#endif + +/*===========================================================================*/ +/* Driver interrupt handlers. */ +/*===========================================================================*/ + +/** + * @brief UART0 IRQ handler. + * + * @isr + */ +#if LPC_SERIAL_USE_UART0 || defined(__DOXYGEN__) +CH_IRQ_HANDLER(Vector94) { + + CH_IRQ_PROLOGUE(); + + serve_interrupt(&SD1); + + CH_IRQ_EPILOGUE(); +} +#endif + +/*===========================================================================*/ +/* Driver exported functions. */ +/*===========================================================================*/ + +/** + * @brief Low level serial driver initialization. + * + * @notapi + */ +void sd_lld_init(void) { + +#if LPC_SERIAL_USE_UART0 + sdObjectInit(&SD1, NULL, notify1); + SD1.uart = LPC_UART; + LPC_IOCON->PIO1_6 = 0xC1; /* RDX without resistors. */ + LPC_IOCON->PIO1_7 = 0xC1; /* TDX without resistors. */ +#endif +} + +/** + * @brief Low level serial driver configuration and (re)start. + * + * @param[in] sdp pointer to a @p SerialDriver object + * @param[in] config the architecture-dependent serial driver configuration. + * If this parameter is set to @p NULL then a default + * configuration is used. + * + * @notapi + */ +void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) { + + if (config == NULL) + config = &default_config; + + if (sdp->state == SD_STOP) { +#if LPC_SERIAL_USE_UART0 + if (&SD1 == sdp) { + LPC_SYSCON->SYSAHBCLKCTRL |= (1 << 12); + LPC_SYSCON->UARTCLKDIV = LPC_SERIAL_UART0CLKDIV; + nvicEnableVector(UART_IRQn, + CORTEX_PRIORITY_MASK(LPC_SERIAL_UART0_IRQ_PRIORITY)); + } +#endif + } + uart_init(sdp, config); +} + +/** + * @brief Low level serial driver stop. + * @details De-initializes the UART, stops the associated clock, resets the + * interrupt vector. + * + * @param[in] sdp pointer to a @p SerialDriver object + * + * @notapi + */ +void sd_lld_stop(SerialDriver *sdp) { + + if (sdp->state == SD_READY) { + uart_deinit(sdp->uart); +#if LPC_SERIAL_USE_UART0 + if (&SD1 == sdp) { + LPC_SYSCON->UARTCLKDIV = 0; + LPC_SYSCON->SYSAHBCLKCTRL &= ~(1 << 12); + nvicDisableVector(UART_IRQn); + return; + } +#endif + } +} + +#endif /* HAL_USE_SERIAL */ + +/** @} */ diff --git a/os/hal/platforms/LPC11Uxx/serial_lld.h b/os/hal/platforms/LPC11Uxx/serial_lld.h new file mode 100644 index 000000000..124ce418f --- /dev/null +++ b/os/hal/platforms/LPC11Uxx/serial_lld.h @@ -0,0 +1,210 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, + 2011,2012 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file LPC11Uxx/serial_lld.h + * @brief LPC11Uxx low level serial driver header. + * + * @addtogroup SERIAL + * @{ + */ + +#ifndef _SERIAL_LLD_H_ +#define _SERIAL_LLD_H_ + +#if HAL_USE_SERIAL || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +#define IIR_SRC_MASK 0x0F +#define IIR_SRC_NONE 0x01 +#define IIR_SRC_MODEM 0x00 +#define IIR_SRC_TX 0x02 +#define IIR_SRC_RX 0x04 +#define IIR_SRC_ERROR 0x06 +#define IIR_SRC_TIMEOUT 0x0C + +#define IER_RBR 1 +#define IER_THRE 2 +#define IER_STATUS 4 + +#define LCR_WL5 0 +#define LCR_WL6 1 +#define LCR_WL7 2 +#define LCR_WL8 3 +#define LCR_STOP1 0 +#define LCR_STOP2 4 +#define LCR_NOPARITY 0 +#define LCR_PARITYODD 0x08 +#define LCR_PARITYEVEN 0x18 +#define LCR_PARITYONE 0x28 +#define LCR_PARITYZERO 0x38 +#define LCR_BREAK_ON 0x40 +#define LCR_DLAB 0x80 + +#define FCR_ENABLE 1 +#define FCR_RXRESET 2 +#define FCR_TXRESET 4 +#define FCR_TRIGGER0 0 +#define FCR_TRIGGER1 0x40 +#define FCR_TRIGGER2 0x80 +#define FCR_TRIGGER3 0xC0 + +#define LSR_RBR_FULL 1 +#define LSR_OVERRUN 2 +#define LSR_PARITY 4 +#define LSR_FRAMING 8 +#define LSR_BREAK 0x10 +#define LSR_THRE 0x20 +#define LSR_TEMT 0x40 +#define LSR_RXFE 0x80 + +#define TER_ENABLE 0x80 + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @brief UART0 driver enable switch. + * @details If set to @p TRUE the support for UART0 is included. + * @note The default is @p TRUE . + */ +#if !defined(LPC_SERIAL_USE_UART0) || defined(__DOXYGEN__) +#define LPC_SERIAL_USE_UART0 TRUE +#endif + +/** + * @brief FIFO preload parameter. + * @details Configuration parameter, this values defines how many bytes are + * preloaded in the HW transmit FIFO for each interrupt, the maximum + * value is 16 the minimum is 1. + * @note An high value reduces the number of interrupts generated but can + * also increase the worst case interrupt response time because the + * preload loops. + */ +#if !defined(LPC_SERIAL_FIFO_PRELOAD) || defined(__DOXYGEN__) +#define LPC_SERIAL_FIFO_PRELOAD 16 +#endif + +/** + * @brief UART0 PCLK divider. + */ +#if !defined(LPC_SERIAL_UART0CLKDIV) || defined(__DOXYGEN__) +#define LPC_SERIAL_UART0CLKDIV 1 +#endif + +/** + * @brief UART0 interrupt priority level setting. + */ +#if !defined(LPC_SERIAL_UART0_IRQ_PRIORITY) || defined(__DOXYGEN__) +#define LPC_SERIAL_UART0_IRQ_PRIORITY 3 +#endif + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +#if (LPC_SERIAL_UART0CLKDIV < 1) || (LPC_SERIAL_UART0CLKDIV > 255) +#error "invalid LPC_SERIAL_UART0CLKDIV setting" +#endif + +#if (LPC_SERIAL_FIFO_PRELOAD < 1) || (LPC_SERIAL_FIFO_PRELOAD > 16) +#error "invalid LPC_SERIAL_FIFO_PRELOAD setting" +#endif + +/** + * @brief UART0 clock. + */ +#define LPC_SERIAL_UART0_PCLK \ + (LPC_MAINCLK / LPC_SERIAL_UART0CLKDIV) + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/** + * @brief LPC11xx Serial Driver configuration structure. + * @details An instance of this structure must be passed to @p sdStart() + * in order to configure and start a serial driver operations. + */ +typedef struct { + /** + * @brief Bit rate. + */ + uint32_t sc_speed; + /** + * @brief Initialization value for the LCR register. + */ + uint32_t sc_lcr; + /** + * @brief Initialization value for the FCR register. + */ + uint32_t sc_fcr; +} SerialConfig; + +/** + * @brief @p SerialDriver specific data. + */ +#define _serial_driver_data \ + _base_asynchronous_channel_data \ + /* Driver state.*/ \ + sdstate_t state; \ + /* Input queue.*/ \ + InputQueue iqueue; \ + /* Output queue.*/ \ + OutputQueue oqueue; \ + /* Input circular buffer.*/ \ + uint8_t ib[SERIAL_BUFFERS_SIZE]; \ + /* Output circular buffer.*/ \ + uint8_t ob[SERIAL_BUFFERS_SIZE]; \ + /* End of the mandatory fields.*/ \ + /* Pointer to the USART registers block.*/ \ + LPC_USART_Type *uart; + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +#if LPC_SERIAL_USE_UART0 && !defined(__DOXYGEN__) +extern SerialDriver SD1; +#endif + +#ifdef __cplusplus +extern "C" { +#endif + void sd_lld_init(void); + void sd_lld_start(SerialDriver *sdp, const SerialConfig *config); + void sd_lld_stop(SerialDriver *sdp); +#ifdef __cplusplus +} +#endif + +#endif /* HAL_USE_SERIAL */ + +#endif /* _SERIAL_LLD_H_ */ + +/** @} */