diff options
| -rw-r--r-- | boards/EA_LPCXPRESSO_BB_1114/board.h | 5 | ||||
| -rw-r--r-- | demos/ARMCM0-LPC1114-GCC/halconf.h | 2 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/hal_lld.c | 3 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/hal_lld.h | 13 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/platform.mk | 3 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/serial_lld.c | 22 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/serial_lld.h | 35 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/spi_lld.c | 376 | ||||
| -rw-r--r-- | os/hal/platforms/LPC11xx/spi_lld.h | 349 | 
9 files changed, 771 insertions, 37 deletions
diff --git a/boards/EA_LPCXPRESSO_BB_1114/board.h b/boards/EA_LPCXPRESSO_BB_1114/board.h index 9c0a6161c..59ec8a267 100644 --- a/boards/EA_LPCXPRESSO_BB_1114/board.h +++ b/boards/EA_LPCXPRESSO_BB_1114/board.h @@ -37,6 +37,11 @@  #define SYSOSCCLK               12000000
  /*
 + * SCK0 connection on this board.
 + */
 +#define LPC11xx_SPI_SCK0_SELECTOR SCK0_IS_PIO2_11
 +
 +/*
   * GPIO 0 initial setup.
   * Bit7 - LPCxpresso LED, initially output at low level.   */
 diff --git a/demos/ARMCM0-LPC1114-GCC/halconf.h b/demos/ARMCM0-LPC1114-GCC/halconf.h index 87d0f835d..2c3afda84 100644 --- a/demos/ARMCM0-LPC1114-GCC/halconf.h +++ b/demos/ARMCM0-LPC1114-GCC/halconf.h @@ -130,7 +130,7 @@   * @brief Enables the SPI subsystem.
   */
  #if !defined(CH_HAL_USE_SPI) || defined(__DOXYGEN__)
 -#define CH_HAL_USE_SPI              FALSE
 +#define CH_HAL_USE_SPI              TRUE
  #endif
  /*
 diff --git a/os/hal/platforms/LPC11xx/hal_lld.c b/os/hal/platforms/LPC11xx/hal_lld.c index 8c8460852..efaf4c98f 100644 --- a/os/hal/platforms/LPC11xx/hal_lld.c +++ b/os/hal/platforms/LPC11xx/hal_lld.c @@ -127,9 +127,6 @@ void lpc111x_clock_init(void) {    LPC_SYSCON->SYSAHBCLKDIV = LPC11xx_SYSABHCLK_DIV;
    LPC_SYSCON->SYSAHBCLKCTRL = 0x0001005F;
 -  /* Peripheral clock dividers initialization.*/
 -  LPC_SYSCON->UARTCLKDIV = LPC11xx_UART_PCLK_DIV;
 -
    /* Memory remapping, vectors always in ROM.*/
    LPC_SYSCON->SYSMEMREMAP = 2;
  }
 diff --git a/os/hal/platforms/LPC11xx/hal_lld.h b/os/hal/platforms/LPC11xx/hal_lld.h index 15e9f85e8..35e8db6a6 100644 --- a/os/hal/platforms/LPC11xx/hal_lld.h +++ b/os/hal/platforms/LPC11xx/hal_lld.h @@ -96,14 +96,6 @@  #define LPC11xx_SYSABHCLK_DIV   1
  #endif
 -/**
 - * @brief   UART clock divider.
 - * @note    The value must be chosen between (1...255).
 - */
 -#if !defined(LPC11xx_UART_PCLK_DIV) || defined(__DOXYGEN__)
 -#define LPC11xx_UART_PCLK_DIV   1
 -#endif
 -
  /*===========================================================================*/
  /* Derived constants and error checks.                                       */
  /*===========================================================================*/
 @@ -199,11 +191,6 @@  #define LPC11xx_FLASHCFG_FLASHTIM   2
  #endif
 -/**
 - * @brief   UART clock.
 - */
 -#define  LPC11xx_UART_PCLK  (LPC11xx_MAINCLK / LPC11xx_UART_PCLK_DIV)
 -
  /*===========================================================================*/
  /* Driver data structures and types.                                         */
  /*===========================================================================*/
 diff --git a/os/hal/platforms/LPC11xx/platform.mk b/os/hal/platforms/LPC11xx/platform.mk index 6bff6ed5f..ade33695f 100644 --- a/os/hal/platforms/LPC11xx/platform.mk +++ b/os/hal/platforms/LPC11xx/platform.mk @@ -1,7 +1,8 @@  # List of all the LPC11xx platform files.
  PLATFORMSRC = ${CHIBIOS}/os/hal/platforms/LPC11xx/hal_lld.c \
                ${CHIBIOS}/os/hal/platforms/LPC11xx/pal_lld.c \
 -              ${CHIBIOS}/os/hal/platforms/LPC11xx/serial_lld.c
 +              ${CHIBIOS}/os/hal/platforms/LPC11xx/serial_lld.c \
 +              ${CHIBIOS}/os/hal/platforms/LPC11xx/spi_lld.c
  # Required include directories
  PLATFORMINC = ${CHIBIOS}/os/hal/platforms/LPC11xx
 diff --git a/os/hal/platforms/LPC11xx/serial_lld.c b/os/hal/platforms/LPC11xx/serial_lld.c index 9f782cafe..42bc5ebb3 100644 --- a/os/hal/platforms/LPC11xx/serial_lld.c +++ b/os/hal/platforms/LPC11xx/serial_lld.c @@ -34,7 +34,7 @@  /* Driver exported variables.                                                */
  /*===========================================================================*/
 -#if USE_LPC11xx_UART0 || defined(__DOXYGEN__)
 +#if LPC11xx_SERIAL_USE_UART0 || defined(__DOXYGEN__)
  /** @brief UART0 serial driver identifier.*/
  SerialDriver SD1;
  #endif
 @@ -63,7 +63,7 @@ static const SerialConfig default_config = {  static void uart_init(SerialDriver *sdp, const SerialConfig *config) {
    LPC_UART_TypeDef *u = sdp->uart;
 -  uint32_t div = LPC11xx_UART_PCLK / (config->sc_speed << 4);
 +  uint32_t div = LPC11xx_SERIAL_UART0_PCLK / (config->sc_speed << 4);
    u->LCR = config->sc_lcr | LCR_DLAB;
    u->DLL = div;
    u->DLM = div >> 8;
 @@ -149,7 +149,7 @@ static void serve_interrupt(SerialDriver *sdp) {        break;
      case IIR_SRC_TX:
        {
 -        int i = LPC11xx_UART_FIFO_PRELOAD;
 +        int i = LPC11xx_SERIAL_FIFO_PRELOAD;
          do {
            msg_t b;
 @@ -181,7 +181,7 @@ static void preload(SerialDriver *sdp) {    LPC_UART_TypeDef *u = sdp->uart;
    if (u->LSR & LSR_THRE) {
 -    int i = LPC11xx_UART_FIFO_PRELOAD;
 +    int i = LPC11xx_SERIAL_FIFO_PRELOAD;
      do {
        msg_t b = chOQGetI(&sdp->oqueue);
        if (b < Q_OK) {
 @@ -197,7 +197,7 @@ static void preload(SerialDriver *sdp) {  /**
   * @brief   Driver SD1 output notification.
   */
 -#if USE_LPC11xx_UART0 || defined(__DOXYGEN__)
 +#if LPC11xx_SERIAL_USE_UART0 || defined(__DOXYGEN__)
  static void notify1(void) {
    preload(&SD1);
 @@ -213,7 +213,7 @@ static void notify1(void) {   *
   * @isr
   */
 -#if USE_LPC11xx_UART0 || defined(__DOXYGEN__)
 +#if LPC11xx_SERIAL_USE_UART0 || defined(__DOXYGEN__)
  CH_IRQ_HANDLER(Vector94) {
    CH_IRQ_PROLOGUE();
 @@ -235,7 +235,7 @@ CH_IRQ_HANDLER(Vector94) {   */
  void sd_lld_init(void) {
 -#if USE_LPC11xx_UART0
 +#if LPC11xx_SERIAL_USE_UART0
    sdObjectInit(&SD1, NULL, notify1);
    SD1.uart = LPC_UART;
    LPC_IOCON->PIO1_6 = 0xC1;                 /* RDX without resistors.       */
 @@ -259,11 +259,12 @@ void sd_lld_start(SerialDriver *sdp, const SerialConfig *config) {      config = &default_config;
    if (sdp->state == SD_STOP) {
 -#if USE_LPC11xx_UART0
 +#if LPC11xx_SERIAL_USE_UART0
      if (&SD1 == sdp) {
        LPC_SYSCON->SYSAHBCLKCTRL |= (1 << 12);
 +      LPC_SYSCON->UARTCLKDIV = LPC11xx_SERIAL_UART0CLKDIV;
        NVICEnableVector(UART_IRQn,
 -                       CORTEX_PRIORITY_MASK(LPC11xx_UART0_PRIORITY));
 +                       CORTEX_PRIORITY_MASK(LPC11xx_SERIAL_UART0_IRQ_PRIORITY));
      }
  #endif
    }
 @@ -283,8 +284,9 @@ void sd_lld_stop(SerialDriver *sdp) {    if (sdp->state == SD_READY) {
      uart_deinit(sdp->uart);
 -#if USE_LPC11xx_UART0
 +#if LPC11xx_SERIAL_USE_UART0
      if (&SD1 == sdp) {
 +      LPC_SYSCON->UARTCLKDIV = 0;
        LPC_SYSCON->SYSAHBCLKCTRL &= ~(1 << 12);
        NVICDisableVector(UART_IRQn);
        return;
 diff --git a/os/hal/platforms/LPC11xx/serial_lld.h b/os/hal/platforms/LPC11xx/serial_lld.h index 4a5a69d36..cd2acdbf4 100644 --- a/os/hal/platforms/LPC11xx/serial_lld.h +++ b/os/hal/platforms/LPC11xx/serial_lld.h @@ -88,8 +88,8 @@   * @details If set to @p TRUE the support for UART0 is included.
   * @note    The default is @p TRUE .
   */
 -#if !defined(USE_LPC11xx_UART0) || defined(__DOXYGEN__)
 -#define USE_LPC11xx_UART0           TRUE
 +#if !defined(LPC11xx_SERIAL_USE_UART0) || defined(__DOXYGEN__)
 +#define LPC11xx_SERIAL_USE_UART0            TRUE
  #endif
  /**
 @@ -101,25 +101,42 @@   *          also increase the worst case interrupt response time because the
   *          preload loops.
   */
 -#if !defined(LPC11xx_UART_FIFO_PRELOAD) || defined(__DOXYGEN__)
 -#define LPC11xx_UART_FIFO_PRELOAD   16
 +#if !defined(LPC11xx_SERIAL_FIFO_PRELOAD) || defined(__DOXYGEN__)
 +#define LPC11xx_SERIAL_FIFO_PRELOAD         16
 +#endif
 +
 +/**
 + * @brief   UART0 PCLK divider.
 + */
 +#if !defined(LPC11xx_SERIAL_UART0CLKDIV) || defined(__DOXYGEN__)
 +#define LPC11xx_SERIAL_UART0CLKDIV          1
  #endif
  /**
   * @brief   UART0 interrupt priority level setting.
   */
 -#if !defined(LPC11xx_UART0_PRIORITY) || defined(__DOXYGEN__)
 -#define LPC11xx_UART0_PRIORITY      3
 +#if !defined(LPC11xx_SERIAL_UART0_IRQ_PRIORITY) || defined(__DOXYGEN__)
 +#define LPC11xx_SERIAL_UART0_IRQ_PRIORITY   3
  #endif
  /*===========================================================================*/
  /* Derived constants and error checks.                                       */
  /*===========================================================================*/
 -#if (LPC11xx_UART_FIFO_PRELOAD < 1) || (LPC11xx_UART_FIFO_PRELOAD > 16)
 -#error "invalid LPC11xx_UART_FIFO_PRELOAD setting"
 +#if (LPC11xx_SERIAL_UART0CLKDIV < 1) || (LPC11xx_SERIAL_UART0CLKDIV > 255)
 +#error "invalid LPC11xx_SERIAL_UART0CLKDIV setting"
  #endif
 +#if (LPC11xx_SERIAL_FIFO_PRELOAD < 1) || (LPC11xx_SERIAL_FIFO_PRELOAD > 16)
 +#error "invalid LPC11xx_SERIAL_FIFO_PRELOAD setting"
 +#endif
 +
 +/**
 + * @brief   UART0 clock.
 + */
 +#define  LPC11xx_SERIAL_UART0_PCLK                                          \
 +  (LPC11xx_MAINCLK / LPC11xx_SERIAL_UART0CLKDIV)
 +
  /*===========================================================================*/
  /* Driver data structures and types.                                         */
  /*===========================================================================*/
 @@ -180,7 +197,7 @@ typedef struct {  /* External declarations.                                                    */
  /*===========================================================================*/
 -#if USE_LPC11xx_UART0 && !defined(__DOXYGEN__)
 +#if LPC11xx_SERIAL_USE_UART0 && !defined(__DOXYGEN__)
  extern SerialDriver SD1;
  #endif
 diff --git a/os/hal/platforms/LPC11xx/spi_lld.c b/os/hal/platforms/LPC11xx/spi_lld.c new file mode 100644 index 000000000..b27d71ed0 --- /dev/null +++ b/os/hal/platforms/LPC11xx/spi_lld.c @@ -0,0 +1,376 @@ +/*
 +    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 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 <http://www.gnu.org/licenses/>.
 +*/
 +
 +/**
 + * @file    LPC11xx/spi_lld.c
 + * @brief   LPC11xx low level SPI driver code.
 + *
 + * @addtogroup LPC11xx_SPI
 + * @{
 + */
 +
 +#include "ch.h"
 +#include "hal.h"
 +
 +#if LPC11xx_SPI_USE_SSP0 || defined(__DOXYGEN__)
 +
 +/*===========================================================================*/
 +/* Driver exported variables.                                                */
 +/*===========================================================================*/
 +
 +#if LPC11xx_SPI_USE_SSP0 || defined(__DOXYGEN__)
 +/** @brief SPI1 driver identifier.*/
 +SPIDriver SPID1;
 +#endif
 +
 +#if LPC11xx_SPI_USE_SSP1 || defined(__DOXYGEN__)
 +/** @brief SPI2 driver identifier.*/
 +SPIDriver SPID2;
 +#endif
 +
 +/*===========================================================================*/
 +/* Driver local variables.                                                   */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* Driver local functions.                                                   */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Preloads the transmit FIFO.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + */
 +static void ssp_fifo_preload(SPIDriver *spip) {
 +  LPC_SSP_TypeDef *ssp = spip->spd_ssp;
 +  uint32_t n = spip->spd_txcnt > LPC11xx_SSP_FIFO_DEPTH ?
 +               LPC11xx_SSP_FIFO_DEPTH : spip->spd_txcnt;
 +
 +  while(((ssp->SR & SR_TNF) != 0) && (n > 0)) {
 +    if (spip->spd_txptr != NULL) {
 +      if ((ssp->CR0 & CR0_DSSMASK) > CR0_DSS8BIT)
 +        ssp->DR = *(uint16_t *)spip->spd_txptr++;
 +      else
 +        ssp->DR = *(uint8_t *)spip->spd_txptr++;
 +    }
 +    else
 +      ssp->DR = 0xFFFFFFFF;
 +    n--;
 +    spip->spd_txcnt--;
 +  }
 +}
 +
 +/**
 + * @brief   Common IRQ handler.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + */
 +static void serve_interrupt(SPIDriver *spip) {
 +  LPC_SSP_TypeDef *ssp = spip->spd_ssp;
 +
 +  if ((ssp->MIS & MIS_ROR) != 0) {
 +    /* The overflow condition should never happen because priority is given
 +       to receive but a hook macro is provided anyway...*/
 +    LPC11xx_SPI_SSP_ERROR_HOOK(spip);
 +  }
 +  ssp->ICR = ICR_RT | ICR_ROR;
 +  while ((ssp->SR & SR_RNE) != 0) {
 +    if (spip->spd_rxptr != NULL) {
 +      if ((ssp->CR0 & CR0_DSSMASK) > CR0_DSS8BIT)
 +        *(uint16_t *)spip->spd_rxptr++ = ssp->DR;
 +      else
 +        *(uint8_t *)spip->spd_rxptr++ = ssp->DR;
 +    }
 +    else
 +      (void)ssp->DR;
 +    if (--spip->spd_rxcnt == 0) {
 +      chDbgAssert(spip->spd_txcnt == 0,
 +                  "chSemResetI(), #1", "counter out of synch");
 +      /* Stops the IRQ sources.*/
 +      ssp->IMSC = 0;
 +      /* Portable SPI ISR code defined in the high level driver, note, it is
 +         a macro.*/
 +      _spi_isr_code(spip);
 +      return;
 +    }
 +  }
 +  ssp_fifo_preload(spip);
 +  if (spip->spd_txcnt == 0)
 +    ssp->IMSC = IMSC_ROR | IMSC_RT | IMSC_RX;
 +}
 +
 +/*===========================================================================*/
 +/* Driver interrupt handlers.                                                */
 +/*===========================================================================*/
 +
 +#if LPC11xx_SPI_USE_SSP0 || defined(__DOXYGEN__)
 +/**
 + * @brief   SSP0 interrupt handler.
 + *
 + * @isr
 + */
 +CH_IRQ_HANDLER(Vector90) {
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  serve_interrupt(&SPID1);
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +#endif
 +
 +#if LPC11xx_SPI_USE_SSP1 || defined(__DOXYGEN__)
 +/**
 + * @brief   SSP1 interrupt handler.
 + *
 + * @isr
 + */
 +CH_IRQ_HANDLER(Vector78) {
 +
 +  CH_IRQ_PROLOGUE();
 +
 +  serve_interrupt(&SPID2);
 +
 +  CH_IRQ_EPILOGUE();
 +}
 +#endif
 +
 +/*===========================================================================*/
 +/* Driver exported functions.                                                */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Low level SPI driver initialization.
 + *
 + * @notapi
 + */
 +void spi_lld_init(void) {
 +
 +#if LPC11xx_SPI_USE_SSP0
 +  spiObjectInit(&SPID1);
 +  SPID1.spd_ssp = LPC_SSP0;
 +  LPC_IOCON->SCK_LOC = LPC11xx_SPI_SCK0_SELECTOR;
 +#if LPC11xx_SPI_SCK0_SELECTOR == SCK0_IS_PIO0_10
 +  LPC_IOCON->JTAG_TCK_PIO0_10 = 0xC2;       /* SCK0 without resistors.      */
 +#elif LPC11xx_SPI_SCK0_SELECTOR == SCK0_IS_PIO2_11
 +  LPC_IOCON->PIO2_11 = 0xC1;                /* SCK0 without resistors.      */
 +#else /* LPC11xx_SPI_SCK0_SELECTOR == SCK0_IS_PIO0_6 */
 +  LPC_IOCON->PIO0_6  = 0xC2;                /* SCK0 without resistors.      */
 +#endif
 +  LPC_IOCON->PIO0_8  = 0xC1;                /* MISO0 without resistors.     */
 +  LPC_IOCON->PIO0_9  = 0xC1;                /* MOSI0 without resistors.     */
 +#endif /* LPC11xx_SPI_USE_SSP0 */
 +
 +#if LPC11xx_SPI_USE_SSP1
 +  spiObjectInit(&SPID2);
 +  SPID2.spd_ssp = LPC_SSP1;
 +  LPC_IOCON->PIO2_1  = 0xC2;                /* SCK1 without resistors.      */
 +  LPC_IOCON->PIO2_2  = 0xC2;                /* MISO1 without resistors.     */
 +  LPC_IOCON->PIO2_3  = 0xC2;                /* MOSI1 without resistors.     */
 +#endif /* LPC11xx_SPI_USE_SSP0 */
 +}
 +
 +/**
 + * @brief   Configures and activates the SPI peripheral.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + *
 + * @notapi
 + */
 +void spi_lld_start(SPIDriver *spip) {
 +
 +  if (spip->spd_state == SPI_STOP) {
 +    /* Clock activation.*/
 +#if LPC11xx_SPI_USE_SSP0
 +    if (&SPID1 == spip) {
 +      LPC_SYSCON->SYSAHBCLKCTRL |= (1 << 11);
 +      LPC_SYSCON->SSP0CLKDIV = LPC11xx_SPI_SSP0CLKDIV;
 +      NVICEnableVector(SSP0_IRQn,
 +                       CORTEX_PRIORITY_MASK(LPC11xx_SPI_SSP0_IRQ_PRIORITY));
 +    }
 +#endif
 +#if LPC11xx_SPI_USE_SSP1
 +    if (&SPID2 == spip) {
 +      LPC_SYSCON->SYSAHBCLKCTRL |= (1 << 18);
 +      LPC_SYSCON->SSP1CLKDIV = LPC11xx_SPI_SSP1CLKDIV;
 +      NVICEnableVector(SSP1_IRQn,
 +                       CORTEX_PRIORITY_MASK(LPC11xx_SPI_SSP1_IRQ_PRIORITY));
 +    }
 +#endif
 +  }
 +  /* Configuration.*/
 +  spip->spd_ssp->CR1  = 0;
 +  /* Emptying the receive FIFO, it happens to not be empty while debugging.*/
 +  while (spip->spd_ssp->SR & SR_RNE)
 +    (void) spip->spd_ssp->DR;
 +  spip->spd_ssp->ICR  = ICR_RT | ICR_ROR;
 +  spip->spd_ssp->CR0  = spip->spd_config->spc_cr0;
 +  spip->spd_ssp->CPSR = spip->spd_config->spc_cpsr;
 +  spip->spd_ssp->CR1  = spip->spd_config->spc_cr1 | CR1_SSE;
 +}
 +
 +/**
 + * @brief   Deactivates the SPI peripheral.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + *
 + * @notapi
 + */
 +void spi_lld_stop(SPIDriver *spip) {
 +
 +  if (spip->spd_state != SPI_STOP) {
 +#if LPC11xx_SPI_USE_SSP0
 +    if (&SPID1 == spip) {
 +      LPC_SYSCON->SSP0CLKDIV = 0;
 +      LPC_SYSCON->SYSAHBCLKCTRL &= ~(1 << 11);
 +      NVICDisableVector(SSP0_IRQn);
 +      return;
 +    }
 +#endif
 +#if LPC11xx_SPI_USE_SSP1
 +    if (&SPID2 == spip) {
 +      LPC_SYSCON->SSP1CLKDIV = 0;
 +      LPC_SYSCON->SYSAHBCLKCTRL &= ~(1 << 18);
 +      NVICDisableVector(SSP1_IRQn);
 +      return;
 +    }
 +#endif
 +    spip->spd_ssp->CR1  = 0;
 +    spip->spd_ssp->CR0  = 0;
 +    spip->spd_ssp->CPSR = 0;
 +  }
 +}
 +
 +/**
 + * @brief   Asserts the slave select signal and prepares for transfers.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + *
 + * @notapi
 + */
 +void spi_lld_select(SPIDriver *spip) {
 +
 +  palClearPad(spip->spd_config->spc_ssport, spip->spd_config->spc_sspad);
 +}
 +
 +/**
 + * @brief   Deasserts the slave select signal.
 + * @details The previously selected peripheral is unselected.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + *
 + * @notapi
 + */
 +void spi_lld_unselect(SPIDriver *spip) {
 +
 +  palSetPad(spip->spd_config->spc_ssport, spip->spd_config->spc_sspad);
 +}
 +
 +/**
 + * @brief   Ignores data on the SPI bus.
 + * @details This function transmits a series of idle words on the SPI bus and
 + *          ignores the received data. This function can be invoked even
 + *          when a slave select signal has not been yet asserted.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + * @param[in] n         number of words to be ignored
 + *
 + * @notapi
 + */
 +void spi_lld_ignore(SPIDriver *spip, size_t n) {
 +
 +  spip->spd_rxptr = NULL;
 +  spip->spd_txptr = NULL;
 +  spip->spd_rxcnt = spip->spd_txcnt = n;
 +  ssp_fifo_preload(spip);
 +  spip->spd_ssp->IMSC = IMSC_ROR | IMSC_RT | IMSC_TX | IMSC_RX;
 +}
 +
 +/**
 + * @brief   Exchanges data on the SPI bus.
 + * @details This asynchronous function starts a simultaneous transmit/receive
 + *          operation.
 + * @post    At the end of the operation the configured callback is invoked.
 + * @note    The buffers are organized as uint8_t arrays for data sizes below or
 + *          equal to 8 bits else it is organized as uint16_t arrays.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + * @param[in] n         number of words to be exchanged
 + * @param[in] txbuf     the pointer to the transmit buffer
 + * @param[out] rxbuf    the pointer to the receive buffer
 + *
 + * @notapi
 + */
 +void spi_lld_exchange(SPIDriver *spip, size_t n,
 +                      const void *txbuf, void *rxbuf) {
 +
 +  spip->spd_rxptr = rxbuf;
 +  spip->spd_txptr = txbuf;
 +  spip->spd_rxcnt = spip->spd_txcnt = n;
 +  ssp_fifo_preload(spip);
 +  spip->spd_ssp->IMSC = IMSC_ROR | IMSC_RT | IMSC_TX | IMSC_RX;
 +}
 +
 +/**
 + * @brief   Sends data over the SPI bus.
 + * @details This asynchronous function starts a transmit operation.
 + * @post    At the end of the operation the configured callback is invoked.
 + * @note    The buffers are organized as uint8_t arrays for data sizes below or
 + *          equal to 8 bits else it is organized as uint16_t arrays.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + * @param[in] n         number of words to send
 + * @param[in] txbuf     the pointer to the transmit buffer
 + *
 + * @notapi
 + */
 +void spi_lld_send(SPIDriver *spip, size_t n, const void *txbuf) {
 +
 +  spip->spd_rxptr = NULL;
 +  spip->spd_txptr = txbuf;
 +  spip->spd_rxcnt = spip->spd_txcnt = n;
 +  ssp_fifo_preload(spip);
 +  spip->spd_ssp->IMSC = IMSC_ROR | IMSC_RT | IMSC_TX | IMSC_RX;
 +}
 +
 +/**
 + * @brief   Receives data from the SPI bus.
 + * @details This asynchronous function starts a receive operation.
 + * @post    At the end of the operation the configured callback is invoked.
 + * @note    The buffers are organized as uint8_t arrays for data sizes below or
 + *          equal to 8 bits else it is organized as uint16_t arrays.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object
 + * @param[in] n         number of words to receive
 + * @param[out] rxbuf    the pointer to the receive buffer
 + *
 + * @notapi
 + */
 +void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf) {
 +
 +  spip->spd_rxptr = rxbuf;
 +  spip->spd_txptr = NULL;
 +  spip->spd_rxcnt = spip->spd_txcnt = n;
 +  ssp_fifo_preload(spip);
 +  spip->spd_ssp->IMSC = IMSC_ROR | IMSC_RT | IMSC_TX | IMSC_RX;
 +}
 +
 +#endif /* CH_HAL_USE_SPI */
 +
 +/** @} */
 diff --git a/os/hal/platforms/LPC11xx/spi_lld.h b/os/hal/platforms/LPC11xx/spi_lld.h new file mode 100644 index 000000000..03ac09244 --- /dev/null +++ b/os/hal/platforms/LPC11xx/spi_lld.h @@ -0,0 +1,349 @@ +/*
 +    ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 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 <http://www.gnu.org/licenses/>.
 +*/
 +
 +/**
 + * @file    LPC11xx/spi_lld.h
 + * @brief   LPC11xx low level SPI driver header.
 + *
 + * @addtogroup LPC11xx_SPI
 + * @{
 + */
 +
 +#ifndef _SPI_LLD_H_
 +#define _SPI_LLD_H_
 +
 +#if CH_HAL_USE_SPI || defined(__DOXYGEN__)
 +
 +/*===========================================================================*/
 +/* Driver constants.                                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Hardware FIFO depth. + */
 +#define LPC11xx_SSP_FIFO_DEPTH          8
 +
 +#define CR0_DSSMASK             0x0F
 +#define CR0_DSS4BIT             3
 +#define CR0_DSS5BIT             4
 +#define CR0_DSS6BIT             5
 +#define CR0_DSS7BIT             6
 +#define CR0_DSS8BIT             7
 +#define CR0_DSS9BIT             8
 +#define CR0_DSS10BIT            9
 +#define CR0_DSS11BIT            0xA
 +#define CR0_DSS12BIT            0xB
 +#define CR0_DSS13BIT            0xC
 +#define CR0_DSS14BIT            0xD
 +#define CR0_DSS15BIT            0xE
 +#define CR0_DSS16BIT            0xF
 +#define CR0_FRFSPI              0
 +#define CR0_FRFSSI              0x10
 +#define CR0_FRFMW               0x20
 +#define CR0_CPOL                0x40
 +#define CR0_CPHA                0x80
 +#define CR0_CLOCKRATE(n)        ((n) << 8)
 +
 +#define CR1_LBM                 1
 +#define CR1_SSE                 2
 +#define CR1_MS                  4
 +#define CR1_SOD                 8
 +
 +#define SR_TFE                  1
 +#define SR_TNF                  2
 +#define SR_RNE                  4
 +#define SR_RFF                  8
 +#define SR_BSY                  16
 +
 +#define IMSC_ROR                1
 +#define IMSC_RT                 2
 +#define IMSC_RX                 4
 +#define IMSC_TX                 8
 +
 +#define RIS_ROR                 1
 +#define RIS_RT                  2
 +#define RIS_RX                  4
 +#define RIS_TX                  8
 +
 +#define MIS_ROR                 1
 +#define MIS_RT                  2
 +#define MIS_RX                  4
 +#define MIS_TX                  8
 +
 +#define ICR_ROR                 1
 +#define ICR_RT                  2
 +
 +
 +/**
 + * @brief   SCK0 signal assigned to pin PIO0_10.
 + */
 +#define SCK0_IS_PIO0_10         0
 +
 +/**
 + * @brief   SCK0 signal assigned to pin PIO2_11.
 + */
 +#define SCK0_IS_PIO2_11         1
 +
 +/**
 + * @brief   SCK0 signal assigned to pin PIO0_6.
 + */
 +#define SCK0_IS_PIO0_6          2
 +
 +/*===========================================================================*/
 +/* Driver pre-compile time settings.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   SPI1 driver enable switch.
 + * @details If set to @p TRUE the support for device SSP0 is included.
 + * @note    The default is @p TRUE.
 + */
 +#if !defined(LPC11xx_SPI_USE_SSP0) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_USE_SSP0                TRUE
 +#endif
 +
 +/**
 + * @brief   SPI2 driver enable switch.
 + * @details If set to @p TRUE the support for device SSP1 is included.
 + * @note    The default is @p TRUE.
 + */
 +#if !defined(LPC11xx_SPI_USE_SSP1) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_USE_SSP1                TRUE
 +#endif
 +
 +/**
 + * @brief   SSP0 PCLK divider.
 + */
 +#if !defined(LPC11xx_SPI_SSP0CLKDIV) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SSP0CLKDIV              1
 +#endif
 +
 +/**
 + * @brief   SSP1 PCLK divider.
 + */
 +#if !defined(LPC11xx_SPI_SSP1CLKDIV) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SSP1CLKDIV              1
 +#endif
 +
 +/**
 + * @brief   SPI0 interrupt priority level setting.
 + */
 +#if !defined(LPC11xx_SPI_SSP0_IRQ_PRIORITY) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SSP0_IRQ_PRIORITY       1
 +#endif
 +
 +/**
 + * @brief   SPI1 interrupt priority level setting.
 + */
 +#if !defined(LPC11xx_SPI_SSP1_IRQ_PRIORITY) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SSP1_IRQ_PRIORITY       1
 +#endif
 +
 +/**
 + * @brief   Overflow error hook.
 + * @details The default action is to stop the system.
 + */
 +#if !defined(LPC11xx_SPI_SSP_ERROR_HOOK) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SSP_ERROR_HOOK(spip)    chSysHalt()
 +#endif
 +
 +/**
 + * @brief   SCK0 signal selector. + */
 +#if !defined(LPC11xx_SPI_SCK0_SELECTOR) || defined(__DOXYGEN__)
 +#define LPC11xx_SPI_SCK0_SELECTOR           SCK0_IS_PIO0_10
 +#endif
 +
 +/*===========================================================================*/
 +/* Derived constants and error checks.                                       */
 +/*===========================================================================*/
 +
 +#if (LPC11xx_SPI_SSP0CLKDIV < 1) || (LPC11xx_SPI_SSP0CLKDIV > 255)
 +#error "invalid LPC11xx_SPI_SSP0CLKDIV setting"
 +#endif
 +
 +#if (LPC11xx_SPI_SSP1CLKDIV < 1) || (LPC11xx_SPI_SSP1CLKDIV > 255)
 +#error "invalid LPC11xx_SPI_SSP1CLKDIV setting"
 +#endif
 +
 +#if !LPC11xx_SPI_USE_SSP0 && !LPC11xx_SPI_USE_SSP1
 +#error "SPI driver activated but no SPI peripheral assigned"
 +#endif
 +
 +#if (LPC11xx_SPI_SCK0_SELECTOR != SCK0_IS_PIO0_10) &&                       \
 +    (LPC11xx_SPI_SCK0_SELECTOR != SCK0_IS_PIO2_11) &&                       \
 +    (LPC11xx_SPI_SCK0_SELECTOR != SCK0_IS_PIO0_6)
 +#error "invalid pin assigned to SCK0 signal"
 +#endif
 +
 +/**
 + * @brief   SSP0 clock.
 + */
 +#define  LPC11xx_SERIAL_SSP0_PCLK                                          \
 +  (LPC11xx_MAINCLK / LPC11xx_SERIAL_SSP0CLKDIV)
 +
 +/**
 + * @brief   SSP1 clock.
 + */
 +#define  LPC11xx_SERIAL_SSP1_PCLK                                          \
 +  (LPC11xx_MAINCLK / LPC11xx_SERIAL_SSP1CLKDIV)
 +
 +/*===========================================================================*/
 +/* Driver data structures and types.                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Type of a structure representing an SPI driver.
 + */
 +typedef struct SPIDriver SPIDriver;
 +
 +/**
 + * @brief   SPI notification callback type.
 + *
 + * @param[in] spip      pointer to the @p SPIDriver object triggering the
 + *                      callback
 + */
 +typedef void (*spicallback_t)(SPIDriver *spip);
 +
 +/**
 + * @brief   Driver configuration structure.
 + */
 +typedef struct {
 +  /**
 +   * @brief Operation complete callback or @p NULL.
 +   * @note  In order to use synchronous functions this field must be set to
 +   *        @p NULL, callbacks and synchronous operations are mutually
 +   *        exclusive.
 +   */
 +  spicallback_t         spc_endcb;
 +  /* End of the mandatory fields.*/
 +  /**
 +   * @brief The chip select line port.
 +   */
 +  ioportid_t            spc_ssport;
 +  /**
 +   * @brief The chip select line pad number.
 +   */
 +  uint16_t              spc_sspad;
 +  /**
 +   * @brief SSP CR0 initialization data.
 +   */
 +  uint16_t              spc_cr0;
 +  /**
 +   * @brief SSP CR1 initialization data.
 +   */
 +  uint16_t              spc_cr1;
 +  /**
 +   * @brief SSP CPSR initialization data.
 +   */
 +  uint32_t              spc_cpsr;
 +} SPIConfig;
 +
 +/**
 + * @brief   Structure representing a SPI driver.
 + */
 +struct SPIDriver {
 +  /**
 +   * @brief Driver state.
 +   */
 +  spistate_t            spd_state;
 +  /**
 +   * @brief Current configuration data.
 +   */
 +  const SPIConfig       *spd_config;
 +#if SPI_USE_WAIT || defined(__DOXYGEN__)
 +  /**
 +   * @brief Waiting thread.
 +   */
 +  Thread                *spd_thread;
 +#endif /* SPI_USE_WAIT */
 +#if SPI_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__)
 +#if CH_USE_MUTEXES || defined(__DOXYGEN__)
 +  /**
 +   * @brief Mutex protecting the bus.
 +   */
 +  Mutex                 spd_mutex;
 +#elif CH_USE_SEMAPHORES
 +  Semaphore             spd_semaphore;
 +#endif
 +#endif /* SPI_USE_MUTUAL_EXCLUSION */
 +#if defined(SPI_DRIVER_EXT_FIELDS)
 +  SPI_DRIVER_EXT_FIELDS
 +#endif
 +  /* End of the mandatory fields.*/
 +  /**
 +   * @brief Pointer to the SSP registers block.
 +   */
 +  LPC_SSP_TypeDef       *spd_ssp;
 +  /**
 +   * @brief Number of bytes yet to be received. +   */
 +  uint32_t              spd_rxcnt;
 +  /**
 +   * @brief Receive pointer or @p NULL.
 +   */
 +  void                  *spd_rxptr;
 +  /**
 +   * @brief Number of bytes yet to be transmitted.
 +   */
 +  uint32_t              spd_txcnt;
 +  /**
 +   * @brief Transmit pointer or @p NULL.
 +   */
 +  const void            *spd_txptr;
 +};
 +
 +/*===========================================================================*/
 +/* Driver macros.                                                            */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* External declarations.                                                    */
 +/*===========================================================================*/
 +
 +#if LPC11xx_SPI_USE_SSP0 && !defined(__DOXYGEN__)
 +extern SPIDriver SPID1;
 +#endif
 +
 +#if LPC11xx_SPI_USE_SSP1 && !defined(__DOXYGEN__)
 +extern SPIDriver SPID2;
 +#endif
 +
 +#ifdef __cplusplus
 +extern "C" {
 +#endif
 +  void spi_lld_init(void);
 +  void spi_lld_start(SPIDriver *spip);
 +  void spi_lld_stop(SPIDriver *spip);
 +  void spi_lld_select(SPIDriver *spip);
 +  void spi_lld_unselect(SPIDriver *spip);
 +  void spi_lld_ignore(SPIDriver *spip, size_t n);
 +  void spi_lld_exchange(SPIDriver *spip, size_t n,
 +                        const void *txbuf, void *rxbuf);
 +  void spi_lld_send(SPIDriver *spip, size_t n, const void *txbuf);
 +  void spi_lld_receive(SPIDriver *spip, size_t n, void *rxbuf);
 +#ifdef __cplusplus
 +}
 +#endif
 +
 +#endif /* CH_HAL_USE_SPI */
 +
 +#endif /* _SPI_LLD_H_ */
 +
 +/** @} */
  | 
