summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-06-30 14:26:09 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-06-30 14:26:09 -0600
commit5de8bacfb5dc8af0e3c64de0e632a4d151b46b54 (patch)
treed4075f864f3cd4d6efd006877d6314577ac86ff2 /nuttx/arch
parent9cac2c93ce2a22dc9b6df08ca0993fb2a9b01254 (diff)
downloadpx4-nuttx-5de8bacfb5dc8af0e3c64de0e632a4d151b46b54.tar.gz
px4-nuttx-5de8bacfb5dc8af0e3c64de0e632a4d151b46b54.tar.bz2
px4-nuttx-5de8bacfb5dc8af0e3c64de0e632a4d151b46b54.zip
SAM3/4: Important bugfix. Values read from PIO input pins do not change unless clocking to the PIO block is enabled
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/sama5/sam_hsmci.c24
-rw-r--r--nuttx/arch/arm/src/sama5/sam_pio.c176
-rw-r--r--nuttx/arch/arm/src/sama5/sam_pioirq.c1
3 files changed, 188 insertions, 13 deletions
diff --git a/nuttx/arch/arm/src/sama5/sam_hsmci.c b/nuttx/arch/arm/src/sama5/sam_hsmci.c
index c3983145c..cf90f292c 100644
--- a/nuttx/arch/arm/src/sama5/sam_hsmci.c
+++ b/nuttx/arch/arm/src/sama5/sam_hsmci.c
@@ -2953,17 +2953,19 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno)
/* Configure PIOs for 4-bit, wide-bus operation. NOTE: (1) the chip
* is capable of 8-bit wide bus operation but D4-D7 are not configured,
* (2) any card detection PIOs must be set up in board-specific logic.
+ *
+ * REVISIT: What about Slot B?
*/
sam_configpio(PIO_MCI0_DA0); /* Data 0 of Slot A */
sam_configpio(PIO_MCI0_DA1); /* Data 1 of Slot A */
sam_configpio(PIO_MCI0_DA2); /* Data 2 of Slot A */
sam_configpio(PIO_MCI0_DA3); /* Data 3 of Slot A */
- sam_configpio(PIO_MCI0_CK); /* SD clock */
- sam_configpio(PIO_MCI0_CDA); /* Command/Response */
+ sam_configpio(PIO_MCI0_CK); /* Common SD clock */
+ sam_configpio(PIO_MCI0_CDA); /* Command/Response of Slot A*/
/* Enable the HSMCI0 peripheral clock. This really should be done in
- * sam_enable (as well as disabling peripheal clocks in sam_disable().
+ * sam_enable (as well as disabling peripheral clocks in sam_disable().
*/
sam_hsmci0_enableclk();
@@ -2990,17 +2992,19 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno)
/* Configure PIOs for 4-bit, wide-bus operation. NOTE: (1) the chip
* is capable of 8-bit wide bus operation but D4-D7 are not configured,
* (2) any card detection PIOs must be set up in board-specific logic.
+ *
+ * REVISIT: What about Slot B?
*/
sam_configpio(PIO_MCI1_DA0); /* Data 0 of Slot A */
sam_configpio(PIO_MCI1_DA1); /* Data 1 of Slot A */
sam_configpio(PIO_MCI1_DA2); /* Data 2 of Slot A */
sam_configpio(PIO_MCI1_DA3); /* Data 3 of Slot A */
- sam_configpio(PIO_MCI1_CK); /* SD clock */
- sam_configpio(PIO_MCI1_CDA); /* Command/Response */
+ sam_configpio(PIO_MCI1_CK); /* Common SD clock */
+ sam_configpio(PIO_MCI1_CDA); /* Command/Response of Slot A */
/* Enable the HSMCI1 peripheral clock This really should be done in
- * sam_enable (as well as disabling peripheal clocks in sam_disable().
+ * sam_enable (as well as disabling peripheral clocks in sam_disable().
*/
sam_hsmci1_enableclk();
@@ -3027,17 +3031,19 @@ FAR struct sdio_dev_s *sdio_initialize(int slotno)
/* Configure PIOs for 4-bit, wide-bus operation. NOTE: (1) the chip
* is capable of 8-bit wide bus operation but D4-D7 are not configured,
* (2) any card detection PIOs must be set up in board-specific logic.
+ *
+ * REVISIT: What about Slot B?
*/
sam_configpio(PIO_MCI2_DA0); /* Data 0 of Slot A */
sam_configpio(PIO_MCI2_DA1); /* Data 1 of Slot A */
sam_configpio(PIO_MCI2_DA2); /* Data 2 of Slot A */
sam_configpio(PIO_MCI1_DA3); /* Data 3 of Slot A */
- sam_configpio(PIO_MCI2_DA3); /* SD clock */
- sam_configpio(PIO_MCI2_CDA); /* Command/Response */
+ sam_configpio(PIO_MCI2_CK); /* Common SD clock */
+ sam_configpio(PIO_MCI2_CDA); /* Command/Response of Slot A */
/* Enable the HSMCI2 peripheral clock This really should be done in
- * sam_enable (as well as disabling peripheal clocks in sam_disable().
+ * sam_enable (as well as disabling peripheral clocks in sam_disable().
*/
sam_hsmci1_enableclk();
diff --git a/nuttx/arch/arm/src/sama5/sam_pio.c b/nuttx/arch/arm/src/sama5/sam_pio.c
index 44d1f0103..1dc135fa6 100644
--- a/nuttx/arch/arm/src/sama5/sam_pio.c
+++ b/nuttx/arch/arm/src/sama5/sam_pio.c
@@ -51,9 +51,11 @@
#include "up_internal.h"
#include "up_arch.h"
+#include "chip/sam_pio.h"
+
#include "chip.h"
+#include "sam_periphclks.h"
#include "sam_pio.h"
-#include "chip/sam_pio.h"
/****************************************************************************
* Pre-processor Definitions
@@ -66,6 +68,7 @@
/****************************************************************************
* Private Data
****************************************************************************/
+/* Maps a port number to the standard port character */
#ifdef CONFIG_DEBUG_GPIO
static const char g_portchar[SAM_NPIO] =
@@ -74,6 +77,49 @@
};
#endif
+/* Map a PIO number to the PIO peripheral identifier (PID) */
+
+static const uint8_t g_piopid[SAM_NPIO] =
+{
+ SAM_PID_PIOA, SAM_PID_PIOB, SAM_PID_PIOC, SAM_PID_PIOD, SAM_PID_PIOE
+};
+
+/* Used to determine if a PIO port is configured to support interrupts */
+
+static const bool g_piointterrupts[SAM_NPIO] =
+{
+#ifdef CONFIG_SAMA5_PIOA_IRQ
+ true,
+#else
+ false,
+#endif
+#ifdef CONFIG_SAMA5_PIOB_IRQ
+ true,
+#else
+ false,
+#endif
+#ifdef CONFIG_SAMA5_PIOC_IRQ
+ true,
+#else
+ false,
+#endif
+#ifdef CONFIG_SAMA5_PIOD_IRQ
+ true,
+#else
+ false,
+#endif
+#ifdef CONFIG_SAMA5_PIOE_IRQ
+ true,
+#else
+ false,
+#endif
+#ifdef CONFIG_SAMA5_PIOF_IRQ
+ true,
+#else
+ false,
+#endif
+};
+
/* SAM_PION_VBASE will only be defined if the PIO register blocks are
* contiguous. If not defined, then we need to do a table lookup.
*/
@@ -117,7 +163,7 @@ static inline uintptr_t sam_piobase(pio_pinset_t cfgset)
* Name: sam_piopin
*
* Description:
- * Returun the base address of the PIO register set
+ * Return the base address of the PIO register set
*
****************************************************************************/
@@ -127,6 +173,102 @@ static inline int sam_piopin(pio_pinset_t cfgset)
}
/****************************************************************************
+ * Name: sam_pio_enableclk
+ *
+ * Description:
+ * Enable clocking on the selected PIO
+ *
+ ****************************************************************************/
+
+static void sam_pio_enableclk(pio_pinset_t cfgset)
+{
+ int port = (cfgset & PIO_PORT_MASK) >> PIO_PORT_SHIFT;
+ int pid;
+
+ if (port < SAM_NPIO)
+ {
+ /* Get the peripheral ID associated with the PIO port and enable
+ * clocking to the PIO block.
+ */
+
+ pid = g_piopid[port];
+ if (pid < 32)
+ {
+ sam_enableperiph0(pid);
+ }
+ else
+ {
+ sam_enableperiph1(pid);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: sam_pio_disableclk
+ *
+ * Description:
+ * Disable clocking on the selected PIO if we can. We can that if:
+ *
+ * 1) No pins are configured as PIO inputs (peripheral inputs don't need
+ * clocking, and
+ * 2) Glitch and debounce filtering are not enabled. Currently, this can
+ * only happen if the the pin is a PIO input, but we may need to
+ * implement glitch filtering on peripheral inputs as well in the
+ * future???
+ * 3) The port is not configured for PIO interrupts. At present, the logic
+ * always keeps clocking on to ports that are configured for interrupts,
+ * but that could be dynamically controlled as well be keeping track
+ * of which PIOs have interrupts enabled.
+ *
+ * My! Wouldn't is be much easier to just keep all of the PIO clocks
+ * enabled? Is there a power management downside?
+ *
+ ****************************************************************************/
+
+static void sam_pio_disableclk(pio_pinset_t cfgset)
+{
+ int port = (cfgset & PIO_PORT_MASK) >> PIO_PORT_SHIFT;
+ uintptr_t base;
+ int pid;
+
+ /* Leave clocking enabled for configured interrupt ports */
+
+ if (port < SAM_NPIO && !g_piointerrupt[port])
+ {
+ /* Get the base address of the PIO port */
+
+ base = g_piobase[port];
+
+ /* Are any pins configured as PIO inputs?
+ *
+ * PSR - A bit set to "1" means that the corresponding pin is a PIO
+ * OSR - A bit set to "1" means that the corresponding pin is an output
+ */
+
+ if ((getreg32(base + SAM_PIO_PSR_OFFSET) &
+ ~getreg32(base + SAM_PIO_PSR_OFFSET)) == 0)
+ {
+ /* Any remaining configured pins are either not PIOs or all not
+ * PIO inputs. Disable clocking to this PIO block.
+ *
+ * Get the peripheral ID associated with the PIO port and disable
+ * clocking to the PIO block.
+ */
+
+ pid = g_piopid[port];
+ if (pid < 32)
+ {
+ sam_disableperiph0(pid);
+ }
+ else
+ {
+ sam_disableperiph1(pid);
+ }
+ }
+ }
+}
+
+/****************************************************************************
* Name: sam_configinput
*
* Description:
@@ -198,6 +340,7 @@ static inline int sam_configinput(uintptr_t base, uint32_t pin,
{
regval &= ~pin;
}
+
putreg32(regval, base + SAM_PIO_SCHMITT_OFFSET);
#endif
@@ -234,7 +377,13 @@ static inline int sam_configinput(uintptr_t base, uint32_t pin,
* another, new API... perhaps sam_configfilter()
*/
- return OK;
+ /* "Reading the I/O line levels requires the clock of the PIO Controller
+ * to be enabled, otherwise PIO_PDSR reads the levels present on the I/O
+ * line at the time the clock was disabled."
+ */
+
+ sam_pio_enableclk(cfgset);
+ return OK;
}
/****************************************************************************
@@ -276,7 +425,11 @@ static inline int sam_configoutput(uintptr_t base, uint32_t pin,
}
#endif
- /* Enable the open drain driver if requrested */
+ /* Disable glitch filtering */
+
+ putreg32(pin, base + SAM_PIO_IFDR_OFFSET);
+
+ /* Enable the open drain driver if requested */
if ((cfgset & PIO_CFG_OPENDRAIN) != 0)
{
@@ -302,6 +455,10 @@ static inline int sam_configoutput(uintptr_t base, uint32_t pin,
putreg32(pin, base + SAM_PIO_OER_OFFSET);
putreg32(pin, base + SAM_PIO_PER_OFFSET);
+
+ /* Clocking to the PIO block may no longer be necessary. */
+
+ sam_pio_disableclk(cfgset);
return OK;
}
@@ -347,6 +504,10 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
}
#endif
+ /* Disable glitch filtering */
+
+ putreg32(pin, base + SAM_PIO_IFDR_OFFSET);
+
#ifdef PIO_HAVE_PERIPHCD
/* Configure pin, depending upon the peripheral A, B, C or D
*
@@ -366,6 +527,7 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
{
regval |= pin;
}
+
putreg32(regval, base + SAM_PIO_ABCDSR1_OFFSET);
regval = getreg32(base + SAM_PIO_ABCDSR2_OFFSET);
@@ -378,6 +540,7 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
{
regval |= pin;
}
+
putreg32(regval, base + SAM_PIO_ABCDSR2_OFFSET);
#else
@@ -396,12 +559,17 @@ static inline int sam_configperiph(uintptr_t base, uint32_t pin,
{
regval |= pin;
}
+
putreg32(regval, base + SAM_PIO_ABSR_OFFSET);
#endif
/* Disable PIO functionality */
putreg32(pin, base + SAM_PIO_PDR_OFFSET);
+
+ /* Clocking to the PIO block may no longer be necessary. */
+
+ sam_pio_disableclk(cfgset);
return OK;
}
diff --git a/nuttx/arch/arm/src/sama5/sam_pioirq.c b/nuttx/arch/arm/src/sama5/sam_pioirq.c
index 4557eb48f..f48fc106d 100644
--- a/nuttx/arch/arm/src/sama5/sam_pioirq.c
+++ b/nuttx/arch/arm/src/sama5/sam_pioirq.c
@@ -196,6 +196,7 @@ static int sam_piointerrupt(uint32_t base, int irq0, void *context)
pending &= ~bit;
}
}
+
return OK;
}