mirror of
https://github.com/RIOT-OS/RIOT.git
synced 2025-12-27 15:31:17 +01:00
Merge pull request #20357 from maribu/cpu/msp430/usci
cpu/msp430/f2xx: clean up periph_uart,periph_spi
This commit is contained in:
commit
4b3308cdef
@ -47,36 +47,31 @@ static const msp430_clock_params_t clock_params = {
|
||||
* @name UART configuration
|
||||
* @{
|
||||
*/
|
||||
#define UART_NUMOF (1U)
|
||||
static const uart_conf_t uart_config[] = {
|
||||
{
|
||||
.uart = &usci_a1_as_uart,
|
||||
},
|
||||
};
|
||||
|
||||
#define UART_BASE (&USCI_A1)
|
||||
#define UART_IE (UC1IE)
|
||||
#define UART_IF (UC1IFG)
|
||||
#define UART_IE_RX_BIT (1 << 0)
|
||||
#define UART_IE_TX_BIT (1 << 1)
|
||||
#define UART_RX_PORT (&PORT_3)
|
||||
#define UART_RX_PIN (1 << 7)
|
||||
#define UART_TX_PORT (&PORT_3)
|
||||
#define UART_TX_PIN (1 << 6)
|
||||
#define UART_RX_ISR (USCIAB1RX_VECTOR)
|
||||
#define UART_TX_ISR (USCIAB1TX_VECTOR)
|
||||
#define UART0_RX_ISR USCIAB1RX_VECTOR /**< RX IRQ vector of UART 0 */
|
||||
|
||||
#define UART_NUMOF ARRAY_SIZE(uart_config)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name SPI configuration
|
||||
* @{
|
||||
*/
|
||||
#define SPI_NUMOF (1U)
|
||||
static const spi_conf_t spi_config[] = {
|
||||
{
|
||||
.spi = &usci_b0_as_spi,
|
||||
},
|
||||
{
|
||||
.spi = &usci_b1_as_spi,
|
||||
},
|
||||
};
|
||||
|
||||
/* SPI configuration */
|
||||
#define SPI_BASE (&USCI_B0)
|
||||
#define SPI_IE (IE2)
|
||||
#define SPI_IF (IFG2)
|
||||
#define SPI_IE_RX_BIT (1 << 2)
|
||||
#define SPI_IE_TX_BIT (1 << 3)
|
||||
#define SPI_PIN_MISO GPIO_PIN(P3, 2)
|
||||
#define SPI_PIN_MOSI GPIO_PIN(P3, 1)
|
||||
#define SPI_PIN_CLK GPIO_PIN(P3, 3)
|
||||
#define SPI_NUMOF ARRAY_SIZE(spi_config)
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@ -48,36 +48,28 @@ static const msp430_clock_params_t clock_params = {
|
||||
* @name UART configuration
|
||||
* @{
|
||||
*/
|
||||
#define UART_NUMOF (1U)
|
||||
static const uart_conf_t uart_config[] = {
|
||||
{
|
||||
.uart = &usci_a0_as_uart,
|
||||
},
|
||||
};
|
||||
|
||||
#define UART_BASE (&USCI_A0)
|
||||
#define UART_IE (IE2)
|
||||
#define UART_IF (IFG2)
|
||||
#define UART_IE_RX_BIT (1 << 0)
|
||||
#define UART_IE_TX_BIT (1 << 1)
|
||||
#define UART_RX_PORT (&PORT_3)
|
||||
#define UART_RX_PIN (1 << 5)
|
||||
#define UART_TX_PORT (&PORT_3)
|
||||
#define UART_TX_PIN (1 << 4)
|
||||
#define UART_RX_ISR (USCIAB0RX_VECTOR)
|
||||
#define UART_TX_ISR (USCIAB0TX_VECTOR)
|
||||
#define UART0_RX_ISR USCIAB0RX_VECTOR /**< RX IRQ vector of UART 0 */
|
||||
|
||||
#define UART_NUMOF ARRAY_SIZE(uart_config)
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name SPI configuration
|
||||
* @{
|
||||
*/
|
||||
#define SPI_NUMOF (1U)
|
||||
static const spi_conf_t spi_config[] = {
|
||||
{
|
||||
.spi = &usci_b0_as_spi,
|
||||
},
|
||||
};
|
||||
|
||||
/* SPI configuration */
|
||||
#define SPI_BASE (&USCI_B0)
|
||||
#define SPI_IE (IE2)
|
||||
#define SPI_IF (IFG2)
|
||||
#define SPI_IE_RX_BIT (1 << 2)
|
||||
#define SPI_IE_TX_BIT (1 << 3)
|
||||
#define SPI_PIN_MISO GPIO_PIN(P3, 2)
|
||||
#define SPI_PIN_MOSI GPIO_PIN(P3, 1)
|
||||
#define SPI_PIN_CLK GPIO_PIN(P3, 3)
|
||||
#define SPI_NUMOF ARRAY_SIZE(spi_config)
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@ -3,6 +3,7 @@ CPU_CORE = msp430
|
||||
|
||||
ifneq (,$(filter msp430f2% msp430g2%,$(CPU_MODEL)))
|
||||
CPU_FAM := msp430_f2xx_g2xx
|
||||
FEATURES_PROVIDED += periph_spi_reconfigure
|
||||
endif
|
||||
|
||||
ifneq (,$(filter msp430f1%,$(CPU_MODEL)))
|
||||
|
||||
@ -32,6 +32,31 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Offset of the USCI B registers in an USCI A peripheral
|
||||
*
|
||||
* USCI A peripheral contains the USCI B peripheral registers, but has a few
|
||||
* USCI A specific register in front. Adding this offset to the USCI A base
|
||||
* address results in the base address of the shared registers.
|
||||
*
|
||||
* @see MSP430_USCI_B_FROM_USCI_A
|
||||
*/
|
||||
#define MSP430_USCI_A_B_OFFSET 3U
|
||||
|
||||
/**
|
||||
* @brief "Convert" an USCI A to an USCI B
|
||||
*
|
||||
* This returns the pointer to the part of the USCI A registers that matches
|
||||
* the USCI B register layout, so that an USCI A can be treated as if it is
|
||||
* an USCI B.
|
||||
*
|
||||
* This can be used instead of @ref msp430_usci_b_from_usci_a when needing a
|
||||
* constant initializer. Otherwise @ref msp430_usci_b_from_usci_a is
|
||||
* preferred as it includes type checks this macro doesn't.
|
||||
*/
|
||||
#define MSP430_USCI_B_FROM_USCI_A(usci_a) \
|
||||
((msp430_usci_b_t *)((uintptr_t)(usci_a) + MSP430_USCI_A_B_OFFSET))
|
||||
|
||||
/**
|
||||
* @brief Universal Serial Control Interface Type A (USCI_A) Registers
|
||||
*/
|
||||
@ -74,6 +99,12 @@ typedef struct {
|
||||
#define UCSSEL_UCLKI UCSSEL_0 /**< Clock USCI using CLKI (n/a in SPI mode) */
|
||||
#define UCSSEL_ACLK UCSSEL_1 /**< Clock USCI using auxiliary clock */
|
||||
#define UCSSEL_SMCLK UCSSEL_2 /**< Clock USCI using sub-system master clock */
|
||||
|
||||
#if (UCSSEL0 == 0x40) || DOXYGEN
|
||||
# define UCSSEL_Pos 6 /**< Position of the UCSSEL field in the USCI CTL1 register */
|
||||
#else
|
||||
# error "USSEL field in USCI CTL1 register is at unexpected position"
|
||||
#endif
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
@ -87,12 +118,12 @@ typedef struct {
|
||||
#define UCBRS_MASK UCBRS_7 /**< Bitmask to retrieve the UCRBS field of the
|
||||
USCI modulation control register */
|
||||
#if (UCBRS_7 == 0x0E) || defined(DOXYGEN)
|
||||
#define UCBRS_POS 1 /**< Position of the UCRBS field in the
|
||||
# define UCBRS_Pos 1 /**< Position of the UCRBS field in the
|
||||
UCAxMCTL register */
|
||||
#else
|
||||
/* The datasheet for the whole MCU family states the field is in bits 3-1,
|
||||
* but let's better be safe than sorry here */
|
||||
#error "UCBRS field in the UCAxMCTL register at unexpected position."
|
||||
# error "UCBRS field in the UCAxMCTL register at unexpected position."
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
@ -138,13 +169,13 @@ extern msp430_usci_a_t USCI_A1;
|
||||
*
|
||||
* @details Provided by linker
|
||||
*/
|
||||
extern msp430_usci_a_t USCI_B0;
|
||||
extern msp430_usci_b_t USCI_B0;
|
||||
/**
|
||||
* @brief USCI_B1 register map
|
||||
*
|
||||
* @details Provided by linker
|
||||
*/
|
||||
extern msp430_usci_a_t USCI_B1;
|
||||
extern msp430_usci_b_t USCI_B1;
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@ -75,6 +75,185 @@ typedef enum {
|
||||
#define PERIPH_SPI_NEEDS_TRANSFER_REGS /**< use shared spi_transfer_regs() */
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief Identifiers for USCI instances
|
||||
*
|
||||
* This assigns the four USCI instances (A0, B0, A1, B1) numbers from 0 to 3.
|
||||
*/
|
||||
typedef enum {
|
||||
#ifdef __MSP430_HAS_USCI_AB0__
|
||||
MSP430_USCI_ID_A0, /**< USCI A0 */
|
||||
MSP430_USCI_ID_B0, /**< USCI B0 */
|
||||
#endif
|
||||
#ifdef __MSP430_HAS_USCI_AB1__
|
||||
MSP430_USCI_ID_A1, /**< USCI A1 */
|
||||
MSP430_USCI_ID_B1, /**< USCI B1 */
|
||||
#endif
|
||||
MSP430_USCI_ID_NUMOF /**< Number of USCI IDs (also: number of USCI instances) */
|
||||
} msp430_usci_id_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI configuration
|
||||
*
|
||||
* @details This is intended to be stored in flash.
|
||||
*/
|
||||
typedef struct {
|
||||
msp430_usci_b_t *dev; /**< The USCI device to use */
|
||||
|
||||
REG8 *interrupt_enable; /**< The interrupt enable register matching the USCI */
|
||||
REG8 *interrupt_flag; /**< The interrupt flag register matching the USCI */
|
||||
uint8_t tx_irq_mask; /**< The bitmask to enable the TX IRQ for this USCI*/
|
||||
uint8_t rx_irq_mask; /**< The bitmask to enable the TX IRQ for this USCI */
|
||||
msp430_usci_id_t id; /**< ID of the USCI */
|
||||
} msp430_usci_params_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI clock source
|
||||
*/
|
||||
typedef enum {
|
||||
USCI_CLK_UCLKI = UCSSEL_UCLKI, /**< UCLKI clock source (not supported yet) */
|
||||
USCI_CLK_AUX = UCSSEL_ACLK, /**< auxiliary clock source */
|
||||
USCI_CLK_SUBMAIN = UCSSEL_SMCLK, /**< sub-system master clock source */
|
||||
} msp430_usci_clk_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI prescaler configuration
|
||||
*/
|
||||
typedef struct {
|
||||
msp430_usci_clk_t clk_source; /**< Clock source to use */
|
||||
uint8_t br0; /**< What to write in the BR0 register */
|
||||
uint8_t br1; /**< What to write in the BR1 register */
|
||||
uint8_t mctl; /**< USCI modulation control register */
|
||||
} msp430_usci_prescaler_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI configuration registers
|
||||
*
|
||||
* @details Unlike @ref msp430_usci_params_t this contains configuration that
|
||||
* may depends on runtime settings
|
||||
*/
|
||||
typedef struct {
|
||||
msp430_usci_prescaler_t prescaler; /**< Prescaler configuration */
|
||||
uint8_t ctl0; /**< USCI control register 0 */
|
||||
} msp430_usci_conf_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx UART configuration, CPU level
|
||||
*
|
||||
* The MSP430 F2xx/G2xx has two USCI peripherals which both can be operated in
|
||||
* UART mode. Each is connected to a fixed GPIO for RXD and TXD, respectively.
|
||||
* Hence, there is not much left for the board to configure anyway, so we just
|
||||
* prepare UART configurations at CPU level for the board to refer to. The
|
||||
* unused configuration(s) will be garbage collected by the linker.
|
||||
*/
|
||||
typedef struct {
|
||||
msp430_usci_params_t usci_params; /**< The USCI params */
|
||||
gpio_t rxd; /**< RXD pin */
|
||||
gpio_t txd; /**< TXD pin */
|
||||
} msp430_usci_uart_params_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx UART configuration, board level
|
||||
*/
|
||||
typedef struct {
|
||||
const msp430_usci_uart_params_t *uart; /**< The UART configuration to use */
|
||||
} uart_conf_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx SPI configuration, CPU level
|
||||
*
|
||||
* The MSP430 F2xx/G2xx has two USCI peripherals which both can be operated in
|
||||
* SPI mode. Each is connected to a fixed GPIO for COPI (MOSI), CIPO (MISO),
|
||||
* and SCK, respectively. Hence, there is not much left for the board to
|
||||
* configure anyway, so we just prepare UART configurations at CPU level for
|
||||
* the board to refer to. The unused configuration(s) will be garbage collected
|
||||
* by the linker.
|
||||
*/
|
||||
typedef struct {
|
||||
msp430_usci_params_t usci_params; /**< The USCI parameters */
|
||||
gpio_t miso; /**< CIPO (MISO) pin */
|
||||
gpio_t mosi; /**< COPI (MOSI) pin */
|
||||
gpio_t sck; /**< SCK pin */
|
||||
} msp430_usci_spi_params_t;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx SPI configuration, board level
|
||||
*/
|
||||
typedef struct {
|
||||
const msp430_usci_spi_params_t *spi; /**< The SPI configuration to use */
|
||||
} spi_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Acquire and initialize USCI for use a SPI/UART peripheral
|
||||
*
|
||||
* @param params Parameter identifying the USCI to use
|
||||
* @param conf Configuration to initialize the USCI with
|
||||
*
|
||||
* @note The USCI will be acquired and configured as specified in @p conf.
|
||||
* However, it will still be held in software reset and all interrupts
|
||||
* will be masked and all interrupt flags be cleared.
|
||||
* @warning You cannot enable IRQs while the USCI is still held under reset.
|
||||
* @details As currently only for UART USCI IRQs are actually needed, the
|
||||
* ISR is implemented in the UART driver. If the SPI or I2C driver
|
||||
* would start to make use of IRQs (other than polling for the IRQ
|
||||
* flag to be set), the ISRs would need to be moved to the USCI
|
||||
* driver and call into the UART/SPI/I2C driver, depending on what
|
||||
* driver has currently acquired the USCI.
|
||||
*/
|
||||
void msp430_usci_acquire(const msp430_usci_params_t *params,
|
||||
const msp430_usci_conf_t *conf);
|
||||
|
||||
/**
|
||||
* @brief Release an USCI, so that it can be used to provide other peripherals
|
||||
*
|
||||
* This will also put the USCI in low power mode.
|
||||
*/
|
||||
void msp430_usci_release(const msp430_usci_params_t *params);
|
||||
|
||||
/**
|
||||
* @brief Calculate prescaler settings for the given target frequency
|
||||
*
|
||||
* @param target_hz The clock frequency (in Hz) to generated with the
|
||||
* prescaler
|
||||
*
|
||||
* @return The calculated prescaler settings
|
||||
*
|
||||
* @note This will select the auxiliary clock source for well known UART
|
||||
* symbol rates up to 9600 Bd, if that is running at 32,768 Hz.
|
||||
* Otherwise the submain clock source is selected.
|
||||
*/
|
||||
msp430_usci_prescaler_t msp430_usci_prescale(uint32_t target_hz);
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI A0 in UART configuration
|
||||
*/
|
||||
extern const msp430_usci_uart_params_t usci_a0_as_uart;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI A1 in UART configuration
|
||||
*/
|
||||
extern const msp430_usci_uart_params_t usci_a1_as_uart;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI A0 in SPI configuration
|
||||
*/
|
||||
extern const msp430_usci_spi_params_t usci_a0_as_spi;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI A1 in SPI configuration
|
||||
*/
|
||||
extern const msp430_usci_spi_params_t usci_a1_as_spi;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI B0 in SPI configuration
|
||||
*/
|
||||
extern const msp430_usci_spi_params_t usci_b0_as_spi;
|
||||
|
||||
/**
|
||||
* @brief MSP430 F2xx/G2xx USCI B1 in SPI configuration
|
||||
*/
|
||||
extern const msp430_usci_spi_params_t usci_b1_as_spi;
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -6,12 +6,13 @@ MODULE = periph
|
||||
# family it is the (incompatible) USCI.
|
||||
ifeq (msp430_x1xx,$(CPU_FAM))
|
||||
SERIAL_IP_BLOCK := usart
|
||||
SRC += $(SERIAL_IP_BLOCK).c
|
||||
endif
|
||||
ifeq (msp430_f2xx_g2xx,$(CPU_FAM))
|
||||
SERIAL_IP_BLOCK := usci
|
||||
endif
|
||||
|
||||
SRC += $(SERIAL_IP_BLOCK).c
|
||||
|
||||
# select family specific peripheral drivers.
|
||||
ifneq (,$(filter periph_uart,$(USEMODULE)))
|
||||
SRC += uart_$(SERIAL_IP_BLOCK).c
|
||||
|
||||
@ -25,22 +25,27 @@
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#include "compiler_hints.h"
|
||||
#include "cpu.h"
|
||||
#include "mutex.h"
|
||||
#include "periph/spi.h"
|
||||
|
||||
/**
|
||||
* @brief Mutex for locking the SPI device
|
||||
*/
|
||||
static mutex_t spi_lock = MUTEX_INIT;
|
||||
/* caching most recently used SPI configuration */
|
||||
static msp430_usci_conf_t _confs[SPI_NUMOF];
|
||||
/* clock frequency for which the SPI configuration was cached */
|
||||
static uint32_t _conf_clks[SPI_NUMOF];
|
||||
/* the USCI is using a mutex already, but we need to guard the access to the
|
||||
* configuration cache with a mutex as well */
|
||||
static mutex_t _locks[SPI_NUMOF];
|
||||
|
||||
void spi_init(spi_t bus)
|
||||
{
|
||||
assert((unsigned)bus < SPI_NUMOF);
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
/* `spi_init()` should be done only once during boot-up */
|
||||
assert(_conf_clks[bus] == 0);
|
||||
|
||||
/* reset SPI device */
|
||||
SPI_BASE->CTL1 = UCSWRST;
|
||||
SPI_BASE->CTL1 |= UCSSEL_SMCLK;
|
||||
/* spi_init_pins() unlocks a mutex, so initializing it locked here */
|
||||
_locks[bus] = (mutex_t)MUTEX_INIT_LOCKED;
|
||||
|
||||
/* trigger the pin configuration */
|
||||
spi_init_pins(bus);
|
||||
@ -48,56 +53,73 @@ void spi_init(spi_t bus)
|
||||
|
||||
void spi_init_pins(spi_t bus)
|
||||
{
|
||||
(void)bus;
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
const msp430_usci_spi_params_t *params = spi_config[bus].spi;
|
||||
|
||||
gpio_periph_mode(SPI_PIN_MISO, true);
|
||||
gpio_periph_mode(SPI_PIN_MOSI, true);
|
||||
gpio_periph_mode(SPI_PIN_CLK, true);
|
||||
gpio_init(params->miso, GPIO_IN);
|
||||
gpio_periph_mode(params->miso, true);
|
||||
gpio_init(params->mosi, GPIO_OUT);
|
||||
gpio_periph_mode(params->mosi, true);
|
||||
gpio_init(params->sck, GPIO_OUT);
|
||||
gpio_periph_mode(params->sck, true);
|
||||
|
||||
mutex_unlock(&_locks[bus]);
|
||||
}
|
||||
|
||||
void spi_deinit_pins(spi_t bus)
|
||||
{
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
const msp430_usci_spi_params_t *params = spi_config[bus].spi;
|
||||
mutex_lock(&_locks[bus]);
|
||||
|
||||
gpio_periph_mode(params->miso, true);
|
||||
gpio_periph_mode(params->mosi, true);
|
||||
gpio_periph_mode(params->sck, true);
|
||||
}
|
||||
|
||||
void spi_acquire(spi_t bus, spi_cs_t cs, spi_mode_t mode, spi_clk_t clk)
|
||||
{
|
||||
(void)bus;
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
(void)cs;
|
||||
assert((unsigned)bus < SPI_NUMOF);
|
||||
assert(clk != SPI_CLK_10MHZ);
|
||||
const msp430_usci_params_t *usci = &spi_config[bus].spi->usci_params;
|
||||
|
||||
/* lock the bus */
|
||||
mutex_lock(&spi_lock);
|
||||
mutex_lock(&_locks[bus]);
|
||||
|
||||
/* calculate baudrate */
|
||||
uint32_t br = msp430_submain_clock_freq() / clk;
|
||||
/* make sure the is not smaller then 2 */
|
||||
if (br < 2) {
|
||||
br = 2;
|
||||
if (_conf_clks[bus] != clk) {
|
||||
/* prescaler not cached, recomputing */
|
||||
_confs[bus].prescaler = msp430_usci_prescale(clk);
|
||||
/* no modulation setting in SPI mode */
|
||||
_confs[bus].prescaler.mctl = 0;
|
||||
}
|
||||
SPI_BASE->BR0 = (uint8_t)br;
|
||||
SPI_BASE->BR1 = (uint8_t)(br >> 8);
|
||||
|
||||
/* configure bus mode */
|
||||
/* configure mode */
|
||||
SPI_BASE->CTL0 = (UCSYNC | UCMST | UCMODE_0 | UCMSB | mode);
|
||||
/* release from software reset */
|
||||
SPI_BASE->CTL1 &= ~(UCSWRST);
|
||||
/* Repopulate CTL0 register settings every time. This is rather cheap
|
||||
* compared to the prescaler configuration and allows reusing the prescaler
|
||||
* across SPI modes */
|
||||
_confs[bus].ctl0 = UCSYNC | UCMST | UCMODE_0 | UCMSB | mode;
|
||||
|
||||
msp430_usci_acquire(usci, &_confs[bus]);
|
||||
|
||||
/* finally, pull USCI out of reset */
|
||||
usci->dev->CTL1 &= ~UCSWRST;
|
||||
}
|
||||
|
||||
void spi_release(spi_t bus)
|
||||
{
|
||||
(void)bus;
|
||||
/* put SPI device back in reset state */
|
||||
SPI_BASE->CTL1 |= UCSWRST;
|
||||
|
||||
/* release the bus */
|
||||
mutex_unlock(&spi_lock);
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
/* unlock in reverse order */
|
||||
msp430_usci_release(&spi_config[bus].spi->usci_params);
|
||||
mutex_unlock(&_locks[bus]);
|
||||
}
|
||||
|
||||
void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont,
|
||||
const void *out, void *in, size_t len)
|
||||
{
|
||||
(void)bus;
|
||||
assume((unsigned)bus < SPI_NUMOF);
|
||||
|
||||
const uint8_t *out_buf = out;
|
||||
uint8_t *in_buf = in;
|
||||
const msp430_usci_spi_params_t *params = spi_config[bus].spi;
|
||||
const msp430_usci_params_t *usci = ¶ms->usci_params;
|
||||
|
||||
assert(out_buf || in_buf);
|
||||
|
||||
@ -108,26 +130,27 @@ void spi_transfer_bytes(spi_t bus, spi_cs_t cs, bool cont,
|
||||
/* if we only send out data, we do this the fast way... */
|
||||
if (!in_buf) {
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
while (!(SPI_IF & SPI_IE_TX_BIT)) {}
|
||||
SPI_BASE->TXBUF = out_buf[i];
|
||||
while (!(*usci->interrupt_flag & usci->tx_irq_mask)) { }
|
||||
usci->dev->TXBUF = out_buf[i];
|
||||
}
|
||||
|
||||
/* finally we need to wait, until all transfers are complete */
|
||||
while (SPI_BASE->STAT & UCBUSY) {}
|
||||
SPI_BASE->RXBUF;
|
||||
while (usci->dev->STAT & UCBUSY) {}
|
||||
(void)usci->dev->RXBUF;
|
||||
}
|
||||
else if (!out_buf) {
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
SPI_BASE->TXBUF = 0;
|
||||
while (!(SPI_IF & SPI_IE_RX_BIT)) {}
|
||||
in_buf[i] = (char)SPI_BASE->RXBUF;
|
||||
usci->dev->TXBUF = 0;
|
||||
while (!(*usci->interrupt_flag & usci->rx_irq_mask)) { }
|
||||
in_buf[i] = usci->dev->RXBUF;
|
||||
}
|
||||
}
|
||||
else {
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
while (!(SPI_IF & SPI_IE_TX_BIT)) {}
|
||||
SPI_BASE->TXBUF = out_buf[i];
|
||||
while (!(SPI_IF & SPI_IE_RX_BIT)) {}
|
||||
in_buf[i] = (char)SPI_BASE->RXBUF;
|
||||
while (!(*usci->interrupt_flag & usci->tx_irq_mask)) { }
|
||||
usci->dev->TXBUF = out_buf[i];
|
||||
while (!(*usci->interrupt_flag & usci->rx_irq_mask)) { }
|
||||
in_buf[i] = usci->dev->RXBUF;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -19,107 +19,181 @@
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "compiler_hints.h"
|
||||
#include "cpu.h"
|
||||
#include "periph_cpu.h"
|
||||
#include "periph_conf.h"
|
||||
#include "irq.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "periph/uart.h"
|
||||
#include "periph_conf.h"
|
||||
#include "periph_cpu.h"
|
||||
|
||||
/**
|
||||
* @brief Keep track of the interrupt context
|
||||
* @{
|
||||
*/
|
||||
static uart_rx_cb_t ctx_rx_cb;
|
||||
static void *ctx_isr_arg;
|
||||
/** @} */
|
||||
#define ENABLE_DEBUG 0
|
||||
#include "debug.h"
|
||||
|
||||
static int init_base(uart_t uart, uint32_t baudrate);
|
||||
static uart_isr_ctx_t _isr_ctx[UART_NUMOF];
|
||||
static msp430_usci_conf_t _confs[UART_NUMOF];
|
||||
|
||||
static void uart_rx_isr(uintptr_t uart);
|
||||
|
||||
void uart_init_pins(uart_t uart)
|
||||
{
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
const msp430_usci_uart_params_t *params = uart_config[uart].uart;
|
||||
|
||||
gpio_set(params->txd);
|
||||
gpio_init(params->txd, GPIO_OUT);
|
||||
gpio_periph_mode(params->txd, true);
|
||||
|
||||
gpio_init(params->rxd, GPIO_IN);
|
||||
gpio_periph_mode(params->rxd, true);
|
||||
}
|
||||
|
||||
void uart_deinit_pins(uart_t uart)
|
||||
{
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
const msp430_usci_uart_params_t *params = uart_config[uart].uart;
|
||||
|
||||
gpio_init(params->txd, GPIO_IN);
|
||||
gpio_periph_mode(params->txd, false);
|
||||
|
||||
gpio_init(params->rxd, GPIO_IN);
|
||||
gpio_periph_mode(params->rxd, false);
|
||||
}
|
||||
|
||||
static void _init(uart_t uart)
|
||||
{
|
||||
const msp430_usci_uart_params_t *params = uart_config[uart].uart;
|
||||
const msp430_usci_conf_t *conf = &_confs[uart];
|
||||
uint8_t enable_rx_irq = 0;
|
||||
/* enable RX IRQ, if callback function is set */
|
||||
if (_isr_ctx[uart].rx_cb) {
|
||||
enable_rx_irq = params->usci_params.rx_irq_mask;
|
||||
}
|
||||
/* acquire and configure USCI */
|
||||
msp430_usci_acquire(¶ms->usci_params, conf);
|
||||
/* reset error stats */
|
||||
params->usci_params.dev->STAT = 0;
|
||||
/* release USCI from reset and enable RX IRQ */
|
||||
params->usci_params.dev->CTL1 &= ~(UCSWRST);
|
||||
/* interrupt enable register is shared between two USCI peripherals, hence
|
||||
* the other may be concurrently be configured */
|
||||
unsigned irq_state = irq_disable();
|
||||
*params->usci_params.interrupt_enable |= enable_rx_irq;
|
||||
irq_restore(irq_state);
|
||||
}
|
||||
|
||||
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
|
||||
{
|
||||
if (init_base(uart, baudrate) < 0) {
|
||||
return -1;
|
||||
}
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
/* prepare configuration */
|
||||
_confs[uart] = (msp430_usci_conf_t){
|
||||
.prescaler = msp430_usci_prescale(baudrate),
|
||||
.ctl0 = 0,
|
||||
};
|
||||
|
||||
/* save interrupt context */
|
||||
ctx_rx_cb = rx_cb;
|
||||
ctx_isr_arg = arg;
|
||||
/* reset interrupt flags and enable RX interrupt */
|
||||
UART_IF &= ~(UART_IE_RX_BIT);
|
||||
UART_IF |= (UART_IE_TX_BIT);
|
||||
UART_IE |= (UART_IE_RX_BIT);
|
||||
UART_IE &= ~(UART_IE_TX_BIT);
|
||||
return 0;
|
||||
}
|
||||
_isr_ctx[uart] = (uart_isr_ctx_t){
|
||||
.rx_cb = rx_cb,
|
||||
.arg = arg,
|
||||
};
|
||||
|
||||
static int init_base(uart_t uart, uint32_t baudrate)
|
||||
{
|
||||
if (uart != 0) {
|
||||
return -1;
|
||||
/* prepare pins */
|
||||
uart_init_pins(uart);
|
||||
|
||||
/* only enable USCI if RX is used, otherwise we enable it on-demand to
|
||||
* allow sharing the USCI and conserve power */
|
||||
|
||||
if (rx_cb) {
|
||||
_init(uart);
|
||||
}
|
||||
|
||||
/* get the default UART for now -> TODO: enable for multiple devices */
|
||||
msp430_usci_a_t *dev = UART_BASE;
|
||||
|
||||
/* put device in reset mode while configuration is going on */
|
||||
dev->CTL1 = UCSWRST;
|
||||
/* configure to UART, using SMCLK in 8N1 mode */
|
||||
dev->CTL1 |= UCSSEL_SMCLK;
|
||||
dev->CTL0 = 0;
|
||||
dev->STAT = 0;
|
||||
/* configure baudrate */
|
||||
uint32_t base = ((msp430_submain_clock_freq() << 7) / baudrate);
|
||||
uint16_t br = (uint16_t)(base >> 7);
|
||||
uint8_t brs = (((base & 0x3f) * 8) >> 7);
|
||||
dev->BR0 = (uint8_t)br;
|
||||
dev->BR1 = (uint8_t)(br >> 8);
|
||||
dev->MCTL = (brs << UCBRS_POS);
|
||||
/* pin configuration -> TODO: move to GPIO driver once implemented */
|
||||
UART_RX_PORT->SEL |= UART_RX_PIN;
|
||||
UART_TX_PORT->SEL |= UART_TX_PIN;
|
||||
UART_RX_PORT->base.DIR &= ~(UART_RX_PIN);
|
||||
UART_TX_PORT->base.DIR |= UART_TX_PIN;
|
||||
/* releasing the software reset bit starts the UART */
|
||||
dev->CTL1 &= ~(UCSWRST);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void uart_write(uart_t uart, const uint8_t *data, size_t len)
|
||||
{
|
||||
(void)uart;
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
while (!(UART_IF & UART_IE_TX_BIT)) {}
|
||||
UART_BASE->TXBUF = data[i];
|
||||
const msp430_usci_params_t *usci = &uart_config[uart].uart->usci_params;
|
||||
bool tx_only = !_isr_ctx[uart].rx_cb;
|
||||
|
||||
/* in TX-only mode, we enable the USCI on-demand */
|
||||
if (tx_only) {
|
||||
_init(uart);
|
||||
}
|
||||
|
||||
while (len--) {
|
||||
while (!(*usci->interrupt_flag & usci->tx_irq_mask)) { }
|
||||
usci->dev->TXBUF = *data++;
|
||||
}
|
||||
|
||||
if (tx_only) {
|
||||
msp430_usci_release(usci);
|
||||
}
|
||||
}
|
||||
|
||||
void uart_poweron(uart_t uart)
|
||||
{
|
||||
(void)uart;
|
||||
/* n/a */
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
if (!_isr_ctx[uart].rx_cb) {
|
||||
/* in TX only mode, the USCI will only be turned on on-demand anyway */
|
||||
return;
|
||||
}
|
||||
|
||||
_init(uart);
|
||||
}
|
||||
|
||||
void uart_poweroff(uart_t uart)
|
||||
{
|
||||
(void)uart;
|
||||
/* n/a */
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
|
||||
if (!_isr_ctx[uart].rx_cb) {
|
||||
/* in TX only mode, the USCI will only be turned on on-demand anyway */
|
||||
return;
|
||||
}
|
||||
|
||||
const msp430_usci_params_t *usci = &uart_config[uart].uart->usci_params;
|
||||
|
||||
msp430_usci_release(usci);
|
||||
}
|
||||
|
||||
ISR(UART_RX_ISR, isr_uart_0_rx)
|
||||
static void uart_rx_isr(uintptr_t uart)
|
||||
{
|
||||
__enter_isr();
|
||||
|
||||
uint8_t stat = UART_BASE->STAT;
|
||||
uint8_t data = (uint8_t)UART_BASE->RXBUF;
|
||||
assume((unsigned)uart < UART_NUMOF);
|
||||
const msp430_usci_params_t *usci = &uart_config[uart].uart->usci_params;
|
||||
uint8_t stat = usci->dev->STAT;
|
||||
uint8_t data = (uint8_t)usci->dev->RXBUF;
|
||||
|
||||
if (stat & (UCFE | UCOE | UCPE | UCBRK)) {
|
||||
/* some error which we do not handle, just do a pseudo read to reset the
|
||||
* status register */
|
||||
(void)data;
|
||||
/* TODO: Add proper error handling */
|
||||
usci->dev->STAT = 0;
|
||||
DEBUG("[uart@%u] Error: %04x\n", (unsigned)uart, (unsigned)stat);
|
||||
}
|
||||
else {
|
||||
ctx_rx_cb(ctx_isr_arg, data);
|
||||
_isr_ctx[uart].rx_cb(_isr_ctx[uart].arg, data);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* only USCI A0 and USCI A1 can be used for UARTs, so at most two ISRS needed */
|
||||
#ifdef UART0_RX_ISR
|
||||
ISR(UART0_RX_ISR, isr_uart0)
|
||||
{
|
||||
__enter_isr();
|
||||
uart_rx_isr(0);
|
||||
__exit_isr();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef UART1_RX_ISR
|
||||
ISR(UART1_RX_ISR, isr_uart1)
|
||||
{
|
||||
__enter_isr();
|
||||
uart_rx_isr(1);
|
||||
__exit_isr();
|
||||
}
|
||||
#endif
|
||||
|
||||
202
cpu/msp430/periph/usci.c
Normal file
202
cpu/msp430/periph/usci.c
Normal file
@ -0,0 +1,202 @@
|
||||
#include "irq.h"
|
||||
#include "macros/math.h"
|
||||
#include "mutex.h"
|
||||
#include "periph_conf.h"
|
||||
#include "periph_cpu.h"
|
||||
|
||||
const msp430_usci_uart_params_t usci_a0_as_uart = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_A0,
|
||||
.dev = MSP430_USCI_B_FROM_USCI_A(&USCI_A0),
|
||||
.interrupt_flag = &UC0IFG,
|
||||
.interrupt_enable = &UC0IE,
|
||||
.tx_irq_mask = UCA0TXIE,
|
||||
.rx_irq_mask = UCA0RXIE,
|
||||
},
|
||||
.txd = GPIO_PIN(P3, 4),
|
||||
.rxd = GPIO_PIN(P3, 5),
|
||||
};
|
||||
|
||||
const msp430_usci_uart_params_t usci_a1_as_uart = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_A1,
|
||||
.dev = MSP430_USCI_B_FROM_USCI_A(&USCI_A1),
|
||||
.interrupt_flag = &UC1IFG,
|
||||
.interrupt_enable = &UC1IE,
|
||||
.tx_irq_mask = UCA1TXIE,
|
||||
.rx_irq_mask = UCA1RXIE,
|
||||
},
|
||||
.txd = GPIO_PIN(P3, 6),
|
||||
.rxd = GPIO_PIN(P3, 7),
|
||||
};
|
||||
|
||||
const msp430_usci_spi_params_t usci_a0_as_spi = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_A0,
|
||||
.dev = MSP430_USCI_B_FROM_USCI_A(&USCI_A0),
|
||||
.interrupt_flag = &UC0IFG,
|
||||
.interrupt_enable = &UC0IE,
|
||||
.tx_irq_mask = UCA0TXIE,
|
||||
.rx_irq_mask = UCA0RXIE,
|
||||
},
|
||||
.mosi = GPIO_PIN(P3, 4),
|
||||
.miso = GPIO_PIN(P3, 5),
|
||||
.sck = GPIO_PIN(P3, 0),
|
||||
};
|
||||
|
||||
const msp430_usci_spi_params_t usci_a1_as_spi = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_A1,
|
||||
.dev = MSP430_USCI_B_FROM_USCI_A(&USCI_A1),
|
||||
.interrupt_flag = &UC1IFG,
|
||||
.interrupt_enable = &UC1IE,
|
||||
.tx_irq_mask = UCA1TXIE,
|
||||
.rx_irq_mask = UCA1RXIE,
|
||||
},
|
||||
.mosi = GPIO_PIN(P3, 7),
|
||||
.miso = GPIO_PIN(P3, 6),
|
||||
.sck = GPIO_PIN(P5, 0),
|
||||
};
|
||||
|
||||
const msp430_usci_spi_params_t usci_b0_as_spi = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_B0,
|
||||
.dev = &USCI_B0,
|
||||
.interrupt_flag = &UC0IFG,
|
||||
.interrupt_enable = &UC0IE,
|
||||
.tx_irq_mask = UCB0TXIE,
|
||||
.rx_irq_mask = UCB0RXIE,
|
||||
},
|
||||
.mosi = GPIO_PIN(P3, 1),
|
||||
.miso = GPIO_PIN(P3, 2),
|
||||
.sck = GPIO_PIN(P3, 3),
|
||||
};
|
||||
|
||||
const msp430_usci_spi_params_t usci_b1_as_spi = {
|
||||
.usci_params = {
|
||||
.id = MSP430_USCI_ID_B1,
|
||||
.dev = &USCI_B1,
|
||||
.interrupt_flag = &UC1IFG,
|
||||
.interrupt_enable = &UC1IE,
|
||||
.tx_irq_mask = UCB1TXIE,
|
||||
.rx_irq_mask = UCB1RXIE,
|
||||
},
|
||||
.mosi = GPIO_PIN(P5, 1),
|
||||
.miso = GPIO_PIN(P5, 2),
|
||||
.sck = GPIO_PIN(P5, 3),
|
||||
};
|
||||
|
||||
static mutex_t _usci_locks[MSP430_USCI_ID_NUMOF] = {
|
||||
MUTEX_INIT,
|
||||
MUTEX_INIT,
|
||||
MUTEX_INIT,
|
||||
MUTEX_INIT,
|
||||
};
|
||||
|
||||
void msp430_usci_acquire(const msp430_usci_params_t *params,
|
||||
const msp430_usci_conf_t *conf)
|
||||
{
|
||||
assume((unsigned)params->id < MSP430_USCI_ID_NUMOF);
|
||||
|
||||
mutex_lock(&_usci_locks[params->id]);
|
||||
msp430_usci_b_t *dev = params->dev;
|
||||
|
||||
/* put device in disabled/reset state */
|
||||
dev->CTL1 = UCSWRST;
|
||||
|
||||
/* apply given configuration */
|
||||
dev->CTL0 = conf->ctl0;
|
||||
dev->CTL1 = conf->prescaler.clk_source | UCSWRST;
|
||||
dev->BR0 = conf->prescaler.br0;
|
||||
dev->BR1 = conf->prescaler.br1;
|
||||
dev->MCTL = conf->prescaler.mctl;
|
||||
|
||||
/* disable USCI IRQs and clear any spurious IRQ flags */
|
||||
uint8_t clear_irq_mask = ~(params->tx_irq_mask | params->rx_irq_mask);
|
||||
unsigned irq_mask = irq_disable();
|
||||
*params->interrupt_flag &= clear_irq_mask;
|
||||
*params->interrupt_enable &= clear_irq_mask;
|
||||
irq_restore(irq_mask);
|
||||
}
|
||||
|
||||
void msp430_usci_release(const msp430_usci_params_t *params)
|
||||
{
|
||||
assume(params->id < MSP430_USCI_ID_NUMOF);
|
||||
|
||||
msp430_usci_b_t *dev = params->dev;
|
||||
|
||||
/* Disable USCI */
|
||||
dev->CTL0 = UCSWRST;
|
||||
|
||||
/* disable USCI IRQs and clear any spurious IRQ flags */
|
||||
uint8_t clear_irq_mask = ~(params->tx_irq_mask | params->rx_irq_mask);
|
||||
unsigned irq_mask = irq_disable();
|
||||
*params->interrupt_enable &= clear_irq_mask;
|
||||
*params->interrupt_flag &= clear_irq_mask;
|
||||
irq_restore(irq_mask);
|
||||
|
||||
/* Release mutex */
|
||||
mutex_unlock(&_usci_locks[params->id]);
|
||||
}
|
||||
|
||||
msp430_usci_prescaler_t msp430_usci_prescale(uint32_t target_hz)
|
||||
{
|
||||
msp430_usci_prescaler_t result = {
|
||||
.mctl = 0,
|
||||
.clk_source = USCI_CLK_SUBMAIN,
|
||||
};
|
||||
|
||||
/* If a watch crystal is used for the auxiliary clock, allow using the
|
||||
* auxiliary clock to be used as clock source for well-known
|
||||
* symbol rates, so that enabling low power modes is possible while
|
||||
* UART RX is active */
|
||||
if ((clock_params.lfxt1_frequency == 32768)
|
||||
&& (clock_params.auxiliary_clock_divier == AUXILIARY_CLOCK_DIVIDE_BY_1)) {
|
||||
assert(msp430_auxiliary_clock_freq() == 32768);
|
||||
result.clk_source = USCI_CLK_AUX;
|
||||
/* The datasheet gives a formula that is used to estimate BRS, but
|
||||
* for optimal accuracy "a detailed error calculation must be performed
|
||||
* for each bit for each UCBRSx setting". We take the pre-calculated
|
||||
* optimal values from the datasheet here. The idea is that if the
|
||||
* clock source is slow ticking, the extra bit timing accuracy may
|
||||
* be needed. Otherwise the estimation will be good enough.
|
||||
*/
|
||||
switch (target_hz) {
|
||||
case 9600:
|
||||
result.mctl = 2U << UCBRS_Pos;
|
||||
result.br0 = 27;
|
||||
return result;
|
||||
case 4800:
|
||||
result.mctl = 6U << UCBRS_Pos;
|
||||
result.br0 = 13;
|
||||
return result;
|
||||
case 2400:
|
||||
result.mctl = 7U << UCBRS_Pos;
|
||||
result.br0 = 6;
|
||||
return result;
|
||||
case 1200:
|
||||
result.mctl = 3U << UCBRS_Pos;
|
||||
result.br0 = 3;
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
/* Otherwise, we compute BR and estimate BRS. We shift left by 7 to avoid
|
||||
* floating point arithmetic. (7 is the largest shit amount for which
|
||||
* clock frequencies with two-digit values in MHz don't exceed the 32 bit
|
||||
* value range.) */
|
||||
uint32_t tmp = DIV_ROUND(msp430_submain_clock_freq() << 7, target_hz);
|
||||
/* BR is the integral part */
|
||||
uint16_t br = tmp >> 7;
|
||||
/* BRS is the fractional part multiplied by 8. We combine the multiplication
|
||||
* by 8 (left-shift by 3) with the right-shift by 7 here to a right-shift
|
||||
* by 4. */
|
||||
uint8_t brs = (tmp & 0x7f) >> 4;
|
||||
result.clk_source = USCI_CLK_SUBMAIN;
|
||||
|
||||
result.br0 = (uint8_t)br;
|
||||
result.br1 = (uint8_t)(br >> 8);
|
||||
result.mctl = brs << UCBRS_Pos;
|
||||
|
||||
return result;
|
||||
}
|
||||
@ -19,5 +19,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stm32f0discovery \
|
||||
telosb \
|
||||
weact-g030f6 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -33,5 +33,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stk3200 \
|
||||
stm32f0discovery \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -5,5 +5,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
msb-430h \
|
||||
nucleo-f031k6 \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -27,5 +27,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
telosb \
|
||||
waspmote-pro \
|
||||
weact-g030f6 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -35,5 +35,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
telosb \
|
||||
waspmote-pro \
|
||||
weact-g030f6 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -14,6 +14,7 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
nucleo-l011k4 \
|
||||
nucleo-l031k6 \
|
||||
olimex-msp430-h1611 \
|
||||
olimex-msp430-h2618 \
|
||||
samd10-xmini \
|
||||
stk3200 \
|
||||
stm32f030f4-demo \
|
||||
|
||||
@ -18,5 +18,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stk3200 \
|
||||
stm32f030f4-demo \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -12,5 +12,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stk3200 \
|
||||
stm32f030f4-demo \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -29,5 +29,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stk3200 \
|
||||
stm32f0discovery \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -8,5 +8,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
nucleo-l011k4 \
|
||||
stm32f030f4-demo \
|
||||
telosb \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -26,5 +26,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stm32l0538-disco \
|
||||
telosb \
|
||||
yunjia-nrf51822 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -24,5 +24,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stm32l0538-disco \
|
||||
telosb \
|
||||
weact-g030f6 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
@ -20,5 +20,4 @@ BOARD_INSUFFICIENT_MEMORY := \
|
||||
stm32l0538-disco \
|
||||
telosb \
|
||||
weact-g030f6 \
|
||||
z1 \
|
||||
#
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user