summaryrefslogtreecommitdiff
path: root/nuttx/configs/sam3u-ek/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-08 00:37:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-08 00:37:18 +0000
commitc87ac73912d8d1dc36944c52526f13d24301cd7a (patch)
tree3ac469cc8242aa9eabf5d99f8fafeee25e167f34 /nuttx/configs/sam3u-ek/src
parent77fac8557262940319c3fa3bc473866d4bb90450 (diff)
downloadpx4-nuttx-c87ac73912d8d1dc36944c52526f13d24301cd7a.tar.gz
px4-nuttx-c87ac73912d8d1dc36944c52526f13d24301cd7a.tar.bz2
px4-nuttx-c87ac73912d8d1dc36944c52526f13d24301cd7a.zip
SAM3U: Add logic to bypass automated control of SPI chip selects
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4032 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/sam3u-ek/src')
-rw-r--r--nuttx/configs/sam3u-ek/src/sam3uek_internal.h12
-rw-r--r--nuttx/configs/sam3u-ek/src/up_lcd.c6
-rw-r--r--nuttx/configs/sam3u-ek/src/up_spi.c104
3 files changed, 107 insertions, 15 deletions
diff --git a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
index 1aa66d517..5b5138960 100644
--- a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
+++ b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
@@ -164,9 +164,17 @@
/* SPI Chip Selects */
-/* Chip select pin connected to the touchscreen controller and to ZigBee module connector. */
+/* Chip select pin connected to the touchscreen controller and to the ZigBee module
+ * connector. Notice that the touchscreen chip select is implemented as a GPIO
+ * OUTPUT that must be controlled by board-specific. This is because the ADS7843E
+ * driver must be able to sample the device BUSY GPIO input between SPI transfers.
+ * However, the AD7843E will tri-state the BUSY input whenever the chip select is
+ * de-asserted. So the only option is to control the chip select manually and hold
+ * it low throughout the SPI transfer.
+ */
-#define GPIO_TSC_NPCS2 GPIO_SPI0_NPCS2_3
+#define GPIO_TSC_NPCS2 (GPIO_OUTPUT|GPIO_CFG_PULLUP|GPIO_OUTPUT_SET|\
+ GPIO_PORT_PIOC|GPIO_PIN14)
/************************************************************************************
* Public Types
diff --git a/nuttx/configs/sam3u-ek/src/up_lcd.c b/nuttx/configs/sam3u-ek/src/up_lcd.c
index 2de563f9b..22cbeca88 100644
--- a/nuttx/configs/sam3u-ek/src/up_lcd.c
+++ b/nuttx/configs/sam3u-ek/src/up_lcd.c
@@ -798,9 +798,9 @@ static int sam3u_setpower(struct lcd_dev_s *dev, int power)
sam3u_gpiowrite(GPIO_LCD_BKL, false);
sam3u_gpiowrite(GPIO_LCD_BKL, false);
sam3u_gpiowrite(GPIO_LCD_BKL, false);
- sam3u_gpiowrite(GPIO_LCD_BKL, true);;
- sam3u_gpiowrite(GPIO_LCD_BKL, true);;
- sam3u_gpiowrite(GPIO_LCD_BKL, true);;
+ sam3u_gpiowrite(GPIO_LCD_BKL, true);
+ sam3u_gpiowrite(GPIO_LCD_BKL, true);
+ sam3u_gpiowrite(GPIO_LCD_BKL, true);
}
/* This delay seems to be required... perhaps because of the big current jump? */
diff --git a/nuttx/configs/sam3u-ek/src/up_spi.c b/nuttx/configs/sam3u-ek/src/up_spi.c
index 515dab2e7..8fed3c48f 100644
--- a/nuttx/configs/sam3u-ek/src/up_spi.c
+++ b/nuttx/configs/sam3u-ek/src/up_spi.c
@@ -107,20 +107,29 @@ void weak_function sam3u_spiinitialize(void)
}
/****************************************************************************
- * Name: sam3u_spiselect, sam3u_spistatus, and sam3u_spicmddata
+ * Name: sam3u_spicsnumber, sam3u_spiselect, sam3u_spistatus, and
+ * sam3u_spicmddata
*
* Description:
* These external functions must be provided by board-specific logic. They
- * are implementations of the select, status, and cmddata methods of the SPI
- * interface defined by struct spi_ops_s (see include/nuttx/spi.h). All
- * other methods including up_spiinitialize()) are provided by common SAM3U
- * logic. To use this common SPI logic on your board:
+ * include:
+ *
+ * o sam3u_spicsnumbe and sam3u_spiselect which are helper functions to
+ * manage the board-specific aspects of the unique SAM3U chip select
+ * architecture.
+ * o sam3u_spistatus and sam3u_spicmddata: Implementations of the status
+ * and cmddata methods of the SPI interface defined by struct spi_ops_
+ * (see include/nuttx/spi.h). All other methods including
+ * up_spiinitialize()) are provided by common SAM3U logic.
+ *
+ * To use this common SPI logic on your board:
*
* 1. Provide logic in sam3u_boardinitialize() to configure SPI chip select
* pins.
- * 2. Provide sam3u_spiselect() and sam3u_spistatus() functions in your
- * board-specific logic. These functions will perform chip selection
- * and status operations using GPIOs in the way your board is configured.
+ * 2. Provide sam3u_spicsnumber(), sam3u_spiselect() and sam3u_spistatus()
+ * functions in your board-specific logic. These functions will perform
+ * chip selection and status operations using GPIOs in the way your board
+ * is configured.
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
* sam3u_spicmddata() functions in your board-specific logic. This
* function will perform cmd/data selection operations using GPIOs in
@@ -134,8 +143,26 @@ void weak_function sam3u_spiinitialize(void)
*
****************************************************************************/
+/****************************************************************************
+ * Name: sam3u_spicsnumber
+ *
+ * Description:
+ * The SAM3U has 4 CS registers for controlling device features. This
+ * function must be provided by board-specific code. Given a logical device
+ * ID, this function returns a number from 0 to 3 that identifies one of
+ * these SAM3U CS resources.
+ *
+ * Input Parameters:
+ * devid - Identifies the (logical) device
+ *
+ * Returned Values:
+ * On success, a CS number from 0 to 3 is returned; A negated errno may
+ * be returned on a failure.
+ *
+ ****************************************************************************/
+
#ifdef CONFIG_SAM3U_SPI
-int sam3u_spiselect(enum spi_dev_e devid)
+int sam3u_spicsnumber(enum spi_dev_e devid)
{
int cs = -EINVAL;
@@ -144,7 +171,7 @@ int sam3u_spiselect(enum spi_dev_e devid)
{
/* Assert the CS pin to the OLED display */
- cs = 2;
+ cs = 2;
}
#endif
@@ -152,6 +179,63 @@ int sam3u_spiselect(enum spi_dev_e devid)
return cs;
}
+/****************************************************************************
+ * Name: sam3u_spiselect
+ *
+ * Description:
+ * PIO chip select pins may be programmed by the board specific logic in
+ * one of two different ways. First, the pins may be programmed as SPI
+ * peripherals. In that case, the pins are completely controlled by the
+ * SPI driver. This method still needs to be provided, but it may be only
+ * a stub.
+ *
+ * An alternative way to program the PIO chip select pins is as a normal
+ * GPIO output. In that case, the automatic control of the CS pins is
+ * bypassed and this function must provide control of the chip select.
+ * NOTE: In this case, the GPIO output pin does *not* have to be the
+ * same as the NPCS pin normal associated with the chip select number.
+ *
+ * Input Parameters:
+ * devid - Identifies the (logical) device
+ * selected - TRUE:Select the device, FALSE:De-select the device
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+void sam3u_spiselect(enum spi_dev_e devid, bool selected)
+{
+ /* The touchscreen chip select is implemented as a GPIO OUTPUT that must
+ * be controlled by this function. This is because the ADS7843E driver
+ * must be able to sample the device BUSY GPIO input between SPI transfers.
+ * However, the AD7843E will tri-state the BUSY input whenever the chip
+ * select is de-asserted. So the only option is to control the chip select
+ * manually and hold it low throughout the SPI transfer.
+ */
+
+#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_ADS7843E)
+ if (devid == SPIDEV_TOUCHSCREEN)
+ {
+ sam3u_gpiowrite(GPIO_TSC_NPCS2, !selected);
+ }
+#endif
+}
+
+/****************************************************************************
+ * Name: sam3u_spistatus
+ *
+ * Description:
+ * Return status information associated with the SPI device.
+ *
+ * Input Parameters:
+ * devid - Identifies the (logical) device
+ *
+ * Returned Values:
+ * Bit-encoded SPI status (see include/nuttx/spi.h.
+ *
+ ****************************************************************************/
+
uint8_t sam3u_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return 0;