summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rwxr-xr-xnuttx/arch/arm/src/imx/imx_spi.c39
-rwxr-xr-xnuttx/arch/arm/src/lm3s/lm3s_ssi.c37
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_spi.c16
3 files changed, 88 insertions, 4 deletions
diff --git a/nuttx/arch/arm/src/imx/imx_spi.c b/nuttx/arch/arm/src/imx/imx_spi.c
index 0a7ca9af0..578e274cd 100755
--- a/nuttx/arch/arm/src/imx/imx_spi.c
+++ b/nuttx/arch/arm/src/imx/imx_spi.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/imx/imx_spi.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -166,6 +166,9 @@ static int spi_interrupt(int irq, void *context);
/* SPI methods */
+#ifndef CONFIG_SPI_OWNBUS
+static int spi_lock(FAR struct spi_dev_s *dev, bool lock);
+#endif
static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency);
static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
static void spi_setbits(FAR struct spi_dev_s *dev, int nbits);
@@ -186,7 +189,9 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t
static const struct spi_ops_s g_spiops =
{
- .lock = 0, /* Not yet implemented */
+#ifndef CONFIG_SPI_OWNBUS
+ .lock = spi_lock,
+#endif
.select = imx_spiselect, /* Provided externally by board logic */
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
@@ -673,6 +678,36 @@ static int spi_interrupt(int irq, void *context)
#endif
/****************************************************************************
+ * Name: spi_lock
+ *
+ * Description:
+ * On SPI busses where there are multiple devices, it will be necessary to
+ * lock SPI to have exclusive access to the busses for a sequence of
+ * transfers. The bus should be locked before the chip is selected. After
+ * locking the SPI bus, the caller should then also call the setfrequency,
+ * setbits, and setmode methods to make sure that the SPI is properly
+ * configured for the device. If the SPI buss is being shared, then it
+ * may have been left in an incompatible state.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_OWNBUS
+static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
+{
+ /* Not implemented */
+
+ return -ENOSYS;
+}
+#endif
+
+/****************************************************************************
* Name: spi_setfrequency
*
* Description:
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
index bbe04bd1b..73b995671 100755
--- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
@@ -232,6 +232,9 @@ static int ssi_interrupt(int irq, void *context);
/* SPI methods */
+#ifndef CONFIG_SPI_OWNBUS
+static int ssi_lock(FAR struct spi_dev_s *dev, bool lock);
+#endif
static void ssi_setfrequencyinternal(struct lm3s_ssidev_s *priv,
uint32_t frequency);
static uint32_t ssi_setfrequency(FAR struct spi_dev_s *dev,
@@ -260,7 +263,9 @@ static void ssi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer,
static const struct spi_ops_s g_spiops =
{
- .lock = 0, /* Not yet implemented */
+#ifndef CONFIG_SPI_OWNBUS
+ .lock = ssi_lock,
+#endif
.select = lm3s_spiselect, /* Provided externally by board logic */
.setfrequency = ssi_setfrequency,
.setmode = ssi_setmode,
@@ -969,6 +974,36 @@ static int ssi_interrupt(int irq, void *context)
#endif
/****************************************************************************
+ * Name: ssi_lock
+ *
+ * Description:
+ * On SPI busses where there are multiple devices, it will be necessary to
+ * lock SPI to have exclusive access to the busses for a sequence of
+ * transfers. The bus should be locked before the chip is selected. After
+ * locking the SPI bus, the caller should then also call the setfrequency,
+ * setbits, and setmode methods to make sure that the SPI is properly
+ * configured for the device. If the SPI buss is being shared, then it
+ * may have been left in an incompatible state.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_OWNBUS
+static int ssi_lock(FAR struct spi_dev_s *dev, bool lock)
+{
+ /* Not implemented */
+
+ return -ENOSYS;
+}
+#endif
+
+/****************************************************************************
* Name: ssi_setfrequency
*
* Description:
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index de0ff2ac5..4b50380eb 100755
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -1,7 +1,7 @@
/************************************************************************************
* arm/arm/src/stm32/stm32_spi.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -137,7 +137,9 @@ struct stm32_spidev_s
sem_t rxsem; /* Wait for RX DMA to complete */
sem_t txsem; /* Wait for TX DMA to complete */
#endif
+#ifndef CONFIG_SPI_OWNBUS
sem_t exclsem; /* Held while chip is selected for mutual exclusion */
+#endif
};
/************************************************************************************
@@ -172,7 +174,9 @@ static inline void spi_dmatxstart(FAR struct stm32_spidev_s *priv);
/* SPI methods */
+#ifndef CONFIG_SPI_OWNBUS
static int spi_lock(FAR struct spi_dev_s *dev, bool lock);
+#endif
static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency);
static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
static void spi_setbits(FAR struct spi_dev_s *dev, int nbits);
@@ -197,7 +201,9 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv);
#ifdef CONFIG_STM32_SPI1
static const struct spi_ops_s g_sp1iops =
{
+#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
+#endif
.select = stm32_spi1select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
@@ -231,7 +237,9 @@ static struct stm32_spidev_s g_spi1dev =
#ifdef CONFIG_STM32_SPI2
static const struct spi_ops_s g_sp2iops =
{
+#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
+#endif
.select = stm32_spi2select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
@@ -265,7 +273,9 @@ static struct stm32_spidev_s g_spi2dev =
#ifdef CONFIG_STM32_SPI3
static const struct spi_ops_s g_sp3iops =
{
+#ifndef CONFIG_SPI_OWNBUS
.lock = spi_lock,
+#endif
.select = stm32_spi3select,
.setfrequency = spi_setfrequency,
.setmode = spi_setmode,
@@ -694,6 +704,7 @@ static void spi_modifycr1(FAR struct stm32_spidev_s *priv, uint16_t setbits, uin
*
****************************************************************************/
+#ifndef CONFIG_SPI_OWNBUS
static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
{
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
@@ -717,6 +728,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
}
return OK;
}
+#endif
/************************************************************************************
* Name: spi_setfrequency
@@ -1185,7 +1197,9 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
/* Initialize the SPI semaphore that enforces mutually exclusive access */
+#ifndef CONFIG_SPI_OWNBUS
sem_init(&priv->exclsem, 0, 1);
+#endif
/* Initialize the SPI semaphores that is used to wait for DMA completion */