From d5e00e594abfe32f3b85caafbeb71d232d5b84d5 Mon Sep 17 00:00:00 2001
From: Hauke Petersen <hauke.petersen@fu-berlin.de>
Date: Tue, 8 Nov 2016 18:20:38 +0100
Subject: [PATCH] cpu/msp430fxyz+boards: adapted to new SPI API

- adapted the SPI driver
- adapted all boards using the CPU
---
 boards/msb-430/Makefile.features           |   1 +
 boards/msb-430/include/periph_conf.h       |   2 +-
 boards/msb-430h/include/periph_conf.h      |   2 +-
 boards/telosb/include/board.h              |   4 +-
 boards/telosb/include/periph_conf.h        |   2 +-
 boards/wsn430-common/include/periph_conf.h |   2 +-
 boards/wsn430-v1_3b/Makefile.features      |   1 +
 boards/wsn430-v1_4/Makefile.features       |   1 +
 boards/z1/include/board.h                  |   4 +-
 boards/z1/include/periph_conf.h            |   2 +-
 cpu/msp430fxyz/include/periph_cpu.h        |  40 ++++
 cpu/msp430fxyz/periph/spi.c                | 263 ++++++---------------
 12 files changed, 130 insertions(+), 194 deletions(-)

diff --git a/boards/msb-430/Makefile.features b/boards/msb-430/Makefile.features
index be3115c5de..90ca83aa3e 100644
--- a/boards/msb-430/Makefile.features
+++ b/boards/msb-430/Makefile.features
@@ -1,6 +1,7 @@
 # Put defined MCU peripherals here (in alphabetical order)
 FEATURES_PROVIDED += periph_gpio
 FEATURES_PROVIDED += periph_timer
+FEATURES_PROVIDED += periph_spi
 FEATURES_PROVIDED += periph_uart
 
 # Various other features (if any)
diff --git a/boards/msb-430/include/periph_conf.h b/boards/msb-430/include/periph_conf.h
index cc7c57b827..97d4d487c7 100644
--- a/boards/msb-430/include/periph_conf.h
+++ b/boards/msb-430/include/periph_conf.h
@@ -75,7 +75,7 @@ extern "C" {
 #define SPI_0_EN            (1U)
 
 /* SPI configuration */
-#define SPI_DEV             (USART_0)
+#define SPI_BASE            (USART_0)
 #define SPI_IE              (SFR->IE1)
 #define SPI_IF              (SFR->IFG1)
 #define SPI_IE_RX_BIT       (1 << 6)
diff --git a/boards/msb-430h/include/periph_conf.h b/boards/msb-430h/include/periph_conf.h
index 0f51ec4a73..3a9c485fa4 100644
--- a/boards/msb-430h/include/periph_conf.h
+++ b/boards/msb-430h/include/periph_conf.h
@@ -77,7 +77,7 @@ extern "C" {
 #define SPI_0_EN            (1U)
 
 /* SPI configuration */
-#define SPI_DEV             (USART_0)
+#define SPI_BASE            (USART_0)
 #define SPI_IE              (SFR->IE1)
 #define SPI_IF              (SFR->IFG1)
 #define SPI_IE_RX_BIT       (1 << 6)
diff --git a/boards/telosb/include/board.h b/boards/telosb/include/board.h
index b84ffc2ab8..4e700d9779 100644
--- a/boards/telosb/include/board.h
+++ b/boards/telosb/include/board.h
@@ -102,8 +102,8 @@ extern "C" {
 /**
  * @brief   Definition of the interface to the CC2420 radio
  */
-#define CC2420_PARAMS_BOARD   {.spi        = SPI_0, \
-                               .spi_clk    = SPI_SPEED_1MHZ , \
+#define CC2420_PARAMS_BOARD   {.spi        = SPI_DEV(0), \
+                               .spi_clk    = SPI_CLK_1MHZ , \
                                .pin_cs     = GPIO_PIN(P4, 2), \
                                .pin_fifo   = GPIO_PIN(P1, 3), \
                                .pin_fifop  = GPIO_PIN(P1, 0), \
diff --git a/boards/telosb/include/periph_conf.h b/boards/telosb/include/periph_conf.h
index d684542de1..e86752e6a3 100644
--- a/boards/telosb/include/periph_conf.h
+++ b/boards/telosb/include/periph_conf.h
@@ -75,7 +75,7 @@ extern "C" {
 #define SPI_0_EN            (1U)
 
 /* SPI configuration */
-#define SPI_DEV             (USART_0)
+#define SPI_BASE            (USART_0)
 #define SPI_IE              (SFR->IE1)
 #define SPI_IF              (SFR->IFG1)
 #define SPI_IE_RX_BIT       (1 << 6)
diff --git a/boards/wsn430-common/include/periph_conf.h b/boards/wsn430-common/include/periph_conf.h
index 80aed6f41c..0ad41ec7a9 100644
--- a/boards/wsn430-common/include/periph_conf.h
+++ b/boards/wsn430-common/include/periph_conf.h
@@ -75,7 +75,7 @@ extern "C" {
 #define SPI_0_EN            (1U)
 
 /* SPI configuration */
-#define SPI_DEV             (USART_0)
+#define SPI_BASE            (USART_0)
 #define SPI_IE              (SFR->IE1)
 #define SPI_IF              (SFR->IFG1)
 #define SPI_IE_RX_BIT       (1 << 6)
diff --git a/boards/wsn430-v1_3b/Makefile.features b/boards/wsn430-v1_3b/Makefile.features
index 8c46a99149..c3dad71213 100644
--- a/boards/wsn430-v1_3b/Makefile.features
+++ b/boards/wsn430-v1_3b/Makefile.features
@@ -1,6 +1,7 @@
 # Put defined MCU peripherals here (in alphabetical order)
 FEATURES_PROVIDED += periph_gpio
 FEATURES_PROVIDED += periph_timer
+FEATURES_PROVIDED += periph_spi
 FEATURES_PROVIDED += periph_uart
 
 # Various other features (if any)
diff --git a/boards/wsn430-v1_4/Makefile.features b/boards/wsn430-v1_4/Makefile.features
index 8c46a99149..c3dad71213 100644
--- a/boards/wsn430-v1_4/Makefile.features
+++ b/boards/wsn430-v1_4/Makefile.features
@@ -1,6 +1,7 @@
 # Put defined MCU peripherals here (in alphabetical order)
 FEATURES_PROVIDED += periph_gpio
 FEATURES_PROVIDED += periph_timer
+FEATURES_PROVIDED += periph_spi
 FEATURES_PROVIDED += periph_uart
 
 # Various other features (if any)
diff --git a/boards/z1/include/board.h b/boards/z1/include/board.h
index d3c1bc7993..1646253bf3 100644
--- a/boards/z1/include/board.h
+++ b/boards/z1/include/board.h
@@ -110,8 +110,8 @@ extern "C" {
 /**
  * @brief   Definition of the interface to the CC2420 radio
  */
-#define CC2420_PARAMS_BOARD         {.spi        = SPI_0, \
-                                     .spi_clk    = SPI_SPEED_5MHZ, \
+#define CC2420_PARAMS_BOARD         {.spi        = SPI_DEV(0), \
+                                     .spi_clk    = SPI_CLK_5MHZ, \
                                      .pin_cs     = GPIO_PIN(P3, 0), \
                                      .pin_fifo   = GPIO_PIN(P1, 3), \
                                      .pin_fifop  = GPIO_PIN(P1, 2), \
diff --git a/boards/z1/include/periph_conf.h b/boards/z1/include/periph_conf.h
index 3196da8df6..a0261978d5 100644
--- a/boards/z1/include/periph_conf.h
+++ b/boards/z1/include/periph_conf.h
@@ -76,7 +76,7 @@ extern "C" {
 
 /* SPI configuration */
 #define SPI_USE_USCI
-#define SPI_DEV             (USCI_0_B_SPI)
+#define SPI_BASE            (USCI_0_B_SPI)
 #define SPI_IE              (SFR->IE2)
 #define SPI_IF              (SFR->IFG2)
 #define SPI_IE_RX_BIT       (1 << 2)
diff --git a/cpu/msp430fxyz/include/periph_cpu.h b/cpu/msp430fxyz/include/periph_cpu.h
index f045de48fe..85ab53d5fb 100644
--- a/cpu/msp430fxyz/include/periph_cpu.h
+++ b/cpu/msp430fxyz/include/periph_cpu.h
@@ -45,6 +45,11 @@ typedef uint16_t gpio_t;
  */
 #define GPIO_PIN(x, y)      ((gpio_t)(((x & 0xff) << 8) | (1 << (y & 0xff))))
 
+/**
+ * @brief   No support for HW chip select...
+ */
+#define SPI_HWCS(x)         (SPI_CS_UNDEF)
+
 #ifndef DOXYGEN
 /**
  * @brief   Override flank selection values
@@ -57,6 +62,40 @@ typedef enum {
     GPIO_BOTH    = 0xab         /**< not supported -> random value*/
 } gpio_flank_t;
 /** @} */
+
+/**
+ * @brief   Override SPI mode selection values
+ */
+#define HAVE_SPI_MODE_T
+#ifndef SPI_USE_USCI
+typedef enum {
+    SPI_MODE_0 = (USART_TCTL_CKPH),                         /**< CPOL=0, CPHA=0 */
+    SPI_MODE_1 = 0,                                         /**< CPOL=0, CPHA=1 */
+    SPI_MODE_2 = (USART_TCTL_CKPL | USART_TCTL_CKPH),       /**< CPOL=1, CPHA=0 */
+    SPI_MODE_3 = (USART_TCTL_CKPL)                          /**< CPOL=1, CPHA=1 */
+} spi_mode_t;
+#else
+typedef enum {
+    SPI_MODE_0 = (USCI_SPI_CTL0_CKPH),                      /**< CPOL=0, CPHA=0 */
+    SPI_MODE_1 = 0,                                         /**< CPOL=0, CPHA=1 */
+    SPI_MODE_2 = (USCI_SPI_CTL0_CKPL | USCI_SPI_CTL0_CKPH), /**< CPOL=1, CPHA=0 */
+    SPI_MODE_3 = (USCI_SPI_CTL0_CKPL)                       /**< CPOL=1, CPHA=1 */
+} spi_mode_t;
+#endif
+/** @} */
+
+/**
+ * @brief   Override SPI clock speed selection values
+ */
+#define HAVE_SPI_CLK_T
+typedef enum {
+    SPI_CLK_100KHZ = 100000,    /**< 100KHz */
+    SPI_CLK_400KHZ = 400000,    /**< 400KHz */
+    SPI_CLK_1MHZ   = 1000000,   /**< 1MHz */
+    SPI_CLK_5MHZ   = 5000000,   /**< 5MHz */
+    SPI_CLK_10MHZ  = 0,         /**< not supported */
+} spi_clk_t;
+/** @} */
 #endif /* ndef DOXYGEN */
 
 /**
@@ -83,6 +122,7 @@ void gpio_periph_mode(gpio_t pin, bool enable);
  * @brief declare needed generic SPI functions
  * @{
  */
+#define PERIPH_SPI_NEEDS_INIT_CS
 #define PERIPH_SPI_NEEDS_TRANSFER_BYTE
 #define PERIPH_SPI_NEEDS_TRANSFER_REG
 #define PERIPH_SPI_NEEDS_TRANSFER_REGS
diff --git a/cpu/msp430fxyz/periph/spi.c b/cpu/msp430fxyz/periph/spi.c
index e7f5fe2602..76a95466ec 100644
--- a/cpu/msp430fxyz/periph/spi.c
+++ b/cpu/msp430fxyz/periph/spi.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (C) 2015 Freie Universität Berlin
+ * Copyright (C) 2015-2016 Freie Universität Berlin
  *
  * This file is subject to the terms and conditions of the GNU Lesser
  * General Public License v2.1. See the file LICENSE in the top level
@@ -25,8 +25,6 @@
 #include "cpu.h"
 #include "mutex.h"
 #include "assert.h"
-#include "periph_cpu.h"
-#include "periph_conf.h"
 #include "periph/spi.h"
 
 /**
@@ -34,233 +32,128 @@
  */
 static mutex_t spi_lock = MUTEX_INIT;
 
-/* per default, we use the legacy MSP430 USART module for UART functionality */
-#ifndef SPI_USE_USCI
 
-int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
+void spi_init(spi_t bus)
 {
-    if (dev != 0) {
-        return -2;
-    }
-
-    /* reset SPI device */
-    SPI_DEV->CTL = USART_CTL_SWRST;
-    /* configure pins */
-    spi_conf_pins(dev);
-    /* configure USART to SPI mode with SMCLK driving it */
-    SPI_DEV->CTL |= (USART_CTL_CHAR | USART_CTL_SYNC | USART_CTL_MM);
-    SPI_DEV->RCTL = 0;
-    SPI_DEV->TCTL = (USART_TCTL_SSEL_SMCLK | USART_TCTL_STC);
-    /* set polarity and phase */
-    switch (conf) {
-        case SPI_CONF_FIRST_RISING:
-            SPI_DEV->TCTL |= USART_TCTL_CKPH;
-            break;
-        case SPI_CONF_SECOND_RISING:
-            /* nothing to be done here */
-            break;
-        case SPI_CONF_FIRST_FALLING:
-            SPI_DEV->TCTL |= (USART_TCTL_CKPH & USART_TCTL_CKPL);
-            break;
-        case SPI_CONF_SECOND_FALLING:
-            SPI_DEV->TCTL |= USART_TCTL_CKPL;
-            break;
-        default:
-            /* invalid clock setting */
-            return -2;
-    }
-    /* configure clock - we use no modulation for now */
-    uint32_t br = CLOCK_CMCLK;
-    switch (speed) {
-        case SPI_SPEED_100KHZ:
-            br /= 100000;
-            break;
-        case SPI_SPEED_400KHZ:
-            br /= 400000;
-            break;
-        case SPI_SPEED_1MHZ:
-            br /= 1000000;
-            break;
-        case SPI_SPEED_5MHZ:
-            br /= 5000000;
-            break;
-        default:
-            /* other clock speeds are not supported */
-            return -1;
-    }
+    assert(bus <= SPI_NUMOF);
 
-    /* make sure the is not smaller then 2 */
-    if (br < 2) {
-        br = 2;
-    }
-
-    SPI_DEV->BR0 = (uint8_t)br;
-    SPI_DEV->BR1 = (uint8_t)(br >> 8);
-    SPI_DEV->MCTL = 0;
+/* we need to differentiate between the legacy SPI device and USCI */
+#ifndef SPI_USE_USCI
+    /* put SPI device in reset state */
+    SPI_BASE->CTL = USART_CTL_SWRST;
+    SPI_BASE->CTL |= (USART_CTL_CHAR | USART_CTL_SYNC | USART_CTL_MM);
+    SPI_BASE->RCTL = 0;
+    SPI_BASE->MCTL = 0;
     /* enable SPI mode */
     SPI_ME |= SPI_ME_BIT;
-    /* release from software reset */
-    SPI_DEV->CTL &= ~(USART_CTL_SWRST);
-    return 0;
+#else
+    /* reset SPI device */
+    SPI_BASE->CTL1 = USCI_SPI_CTL1_SWRST;
+    SPI_BASE->CTL1 |= (USCI_SPI_CTL1_SSEL_SMCLK);
+#endif
+
+    /* trigger the pin configuration */
+    spi_init_pins(bus);
 }
 
-/* we use alternative SPI code in case the board used the USCI module for SPI
- * instead of the (older) USART module */
-#else   /* SPI_USE_USCI */
+void spi_init_pins(spi_t bus)
+{
+    gpio_periph_mode(SPI_PIN_MISO, true);
+    gpio_periph_mode(SPI_PIN_MOSI, true);
+    gpio_periph_mode(SPI_PIN_CLK, true);
+}
 
-int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
+int spi_acquire(spi_t bus, spi_cs_t cs, spi_mode_t mode, spi_clk_t clk)
 {
-    if (dev != 0) {
-        return -2;
+    if (clk == SPI_CLK_10MHZ) {
+        return SPI_NOCLK;
     }
 
-    /* reset SPI device */
-    SPI_DEV->CTL1 |= USCI_SPI_CTL1_SWRST;
-    /* configure pins */
-    spi_conf_pins(dev);
-    /* configure USART to SPI mode with SMCLK driving it */
-    SPI_DEV->CTL0 |= (USCI_SPI_CTL0_UCSYNC | USCI_SPI_CTL0_MST
-                      | USCI_SPI_CTL0_MODE_0 | USCI_SPI_CTL0_MSB);
-    SPI_DEV->CTL1 |= (USCI_SPI_CTL1_SSEL_SMCLK);
-
-    /* set polarity and phase */
-    switch (conf) {
-        case SPI_CONF_FIRST_RISING:
-            SPI_DEV->CTL0 |= USCI_SPI_CTL0_CKPH;
-            break;
-        case SPI_CONF_SECOND_RISING:
-            /* nothing to be done here */
-            break;
-        case SPI_CONF_FIRST_FALLING:
-            SPI_DEV->CTL0 |= (USCI_SPI_CTL0_CKPH & USCI_SPI_CTL0_CKPL);
-            break;
-        case SPI_CONF_SECOND_FALLING:
-            SPI_DEV->CTL0 |= USCI_SPI_CTL0_CKPL;
-            break;
-        default:
-            /* invalid clock setting */
-            return -2;
-    }
-    /* configure clock - we use no modulation for now */
-    uint32_t br = CLOCK_CMCLK;
-    switch (speed) {
-        case SPI_SPEED_100KHZ:
-            br /= 100000;
-            break;
-        case SPI_SPEED_400KHZ:
-            br /= 400000;
-            break;
-        case SPI_SPEED_1MHZ:
-            br /= 1000000;
-            break;
-        case SPI_SPEED_5MHZ:
-            br /= 5000000;
-            break;
-        default:
-            /* other clock speeds are not supported */
-            return -1;
-    }
+    /* lock the bus */
+    mutex_lock(&spi_lock);
 
+    /* calculate baudrate */
+    uint32_t br = CLOCK_CMCLK / clk;
     /* make sure the is not smaller then 2 */
     if (br < 2) {
         br = 2;
     }
+    SPI_BASE->BR0 = (uint8_t)br;
+    SPI_BASE->BR1 = (uint8_t)(br >> 8);
 
-    SPI_DEV->BR0 = (uint8_t)br;
-    SPI_DEV->BR1 = (uint8_t)(br >> 8);
+    /* configure bus mode */
+#ifndef SPI_USE_USCI
+    /* configure mode */
+    SPI_BASE->TCTL = (USART_TCTL_SSEL_SMCLK | USART_TCTL_STC | mode);
     /* release from software reset */
-    SPI_DEV->CTL1 &= ~(USCI_SPI_CTL1_SWRST);
-    return 0;
-}
-
-#endif  /* SPI_USE_USCI */
-
-int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char data))
-{
-    /* not supported so far */
-    (void)dev;
-    (void)conf;
-    (void)cb;
-    return -1;
-}
-
-void spi_transmission_begin(spi_t dev, char reset_val)
-{
-    /* not supported so far */
-    (void)dev;
-    (void)reset_val;
-}
+    SPI_BASE->CTL &= ~(USART_CTL_SWRST);
+#else
+    /* configure mode */
+    SPI_BASE->CTL0 = (USCI_SPI_CTL0_UCSYNC | USCI_SPI_CTL0_MST|
+                     USCI_SPI_CTL0_MODE_0 | USCI_SPI_CTL0_MSB | mode);
+    /* release from software reset */
+    SPI_BASE->CTL1 &= ~(USCI_SPI_CTL1_SWRST);
+#endif
 
-int spi_conf_pins(spi_t dev)
-{
-    (void)dev;
-    gpio_periph_mode(SPI_PIN_MISO, true);
-    gpio_periph_mode(SPI_PIN_MOSI, true);
-    gpio_periph_mode(SPI_PIN_CLK, true);
-    return 0;
+    return SPI_OK;
 }
 
-int spi_acquire(spi_t dev)
+void spi_release(spi_t dev)
 {
-    (void)dev;
-    mutex_lock(&spi_lock);
-    return 0;
-}
+    /* put SPI device back in reset state */
+#ifndef SPI_USE_USCI
+    SPI_BASE->CTL |= (USART_CTL_SWRST);
+#else
+    SPI_BASE->CTL1 |= (USCI_SPI_CTL1_SWRST);
+#endif
 
-int spi_release(spi_t dev)
-{
-    (void)dev;
+    /* release the bus */
     mutex_unlock(&spi_lock);
-    return 0;
 }
 
-int spi_transfer_bytes(spi_t dev, char *out, char *in, unsigned int length)
+void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont,
+                        const void *out, void *in, size_t len)
 {
-    (void)dev;
+    uint8_t *out_buf = (uint8_t *)out;
+    uint8_t *in_buf = (uint8_t *)in;
+
+    assert(out_buf || in_buf);
 
-    assert(out || in);
+    if (cs != SPI_CS_UNDEF) {
+        gpio_clear((gpio_t)cs);
+    }
 
     /* if we only send out data, we do this the fast way... */
-    if (!in) {
-        for (unsigned i = 0; i < length; i++) {
+    if (!in_buf) {
+        for (size_t i = 0; i < len; i++) {
             while (!(SPI_IF & SPI_IE_TX_BIT)) {}
-            SPI_DEV->TXBUF = (uint8_t)out[i];
+            SPI_BASE->TXBUF = (uint8_t)out_buf[i];
         }
         /* finally we need to wait, until all transfers are complete */
 #ifndef SPI_USE_USCI
         while (!(SPI_IF & SPI_IE_TX_BIT) || !(SPI_IF & SPI_IE_RX_BIT)) {}
 #else
-        while (SPI_DEV->STAT & USCI_SPI_STAT_UCBUSY) {}
+        while (SPI_BASE->STAT & USCI_SPI_STAT_UCBUSY) {}
 #endif
-        SPI_DEV->RXBUF;
+        SPI_BASE->RXBUF;
     }
-    else if (!out) {
-        for (unsigned i = 0; i < length; i++) {
-            SPI_DEV->TXBUF = 0;
+    else if (!out_buf) {
+        for (size_t i = 0; i < len; i++) {
+            SPI_BASE->TXBUF = 0;
             while (!(SPI_IF & SPI_IE_RX_BIT)) {}
-            in[i] = (char)SPI_DEV->RXBUF;
+            in_buf[i] = (char)SPI_BASE->RXBUF;
         }
     }
     else {
-        for (unsigned i = 0; i < length; i++) {
+        for (size_t i = 0; i < len; i++) {
             while (!(SPI_IF & SPI_IE_TX_BIT)) {}
-            SPI_DEV->TXBUF = out[i];
+            SPI_BASE->TXBUF = out_buf[i];
             while (!(SPI_IF & SPI_IE_RX_BIT)) {}
-            in[i] = (char)SPI_DEV->RXBUF;
+            in_buf[i] = (char)SPI_BASE->RXBUF;
         }
     }
 
-    return length;
-}
-
-void spi_poweron(spi_t dev)
-{
-    /* not supported so far */
-    (void)dev;
-}
-
-void spi_poweroff(spi_t dev)
-{
-    /* not supported so far */
-    (void)dev;
+    if ((!cont) && (cs != SPI_CS_UNDEF)) {
+        gpio_set((gpio_t)cs);
+    }
 }
-- 
GitLab