summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-27 17:25:35 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-27 17:25:35 +0000
commit0b1a74a038400b61713d4947524b74c3c3d231c0 (patch)
treefba95c4add1ca1c4d8451bcfcbecb89c3102353c /nuttx/arch
parentcfe14dccae1e63f5067ea29d27921fda26d735b2 (diff)
downloadpx4-nuttx-0b1a74a038400b61713d4947524b74c3c3d231c0.tar.gz
px4-nuttx-0b1a74a038400b61713d4947524b74c3c3d231c0.tar.bz2
px4-nuttx-0b1a74a038400b61713d4947524b74c3c3d231c0.zip
Add support for PIC32MX1/2 ANSEL register; Mirtoo NXFFS configuration now uses the Pinquino toolchain by default:
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4984 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-gpio.c38
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-internal.h8
2 files changed, 40 insertions, 6 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-gpio.c b/nuttx/arch/mips/src/pic32mx/pic32mx-gpio.c
index ecff125ad..d138984aa 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-gpio.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-gpio.c
@@ -125,6 +125,15 @@ static inline unsigned int pic32mx_pinno(uint16_t pinset)
return ((pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT);
}
+#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+static inline unsigned int pic32mx_analog(uint16_t pinset)
+{
+ return ((pinset & GPIO_ANALOG_MASK) != 0);
+}
+#else
+# define pic32mx_analog(pinset) (false)
+#endif
+
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -145,6 +154,7 @@ int pic32mx_configgpio(uint16_t cfgset)
{
unsigned int port = pic32mx_portno(cfgset);
unsigned int pin = pic32mx_pinno(cfgset);
+ uint32_t mask = (1 << pin);
uintptr_t base;
/* Verify that the port number is within range */
@@ -160,9 +170,14 @@ int pic32mx_configgpio(uint16_t cfgset)
sched_lock();
if (pic32mx_output(cfgset))
{
+ /* Not analog */
+
+#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+ putreg32(mask, base + PIC32MX_IOPORT_ANSELCLR_OFFSET);
+#endif
/* It is an output; clear the corresponding bit in the TRIS register */
- putreg32(1 << pin, base + PIC32MX_IOPORT_TRISCLR_OFFSET);
+ putreg32(mask, base + PIC32MX_IOPORT_TRISCLR_OFFSET);
/* Is it an open drain output? */
@@ -172,7 +187,7 @@ int pic32mx_configgpio(uint16_t cfgset)
* the ODC register.
*/
- putreg32(1 << pin, base + PIC32MX_IOPORT_ODCSET_OFFSET);
+ putreg32(mask, base + PIC32MX_IOPORT_ODCSET_OFFSET);
}
else
{
@@ -180,7 +195,7 @@ int pic32mx_configgpio(uint16_t cfgset)
* ODC register.
*/
- putreg32(1 << pin, base + PIC32MX_IOPORT_ODCCLR_OFFSET);
+ putreg32(mask, base + PIC32MX_IOPORT_ODCCLR_OFFSET);
}
/* Set the initial output value */
@@ -191,8 +206,21 @@ int pic32mx_configgpio(uint16_t cfgset)
{
/* It is an input; set the corresponding bit in the TRIS register. */
- putreg32(1 << pin, base + PIC32MX_IOPORT_TRISSET_OFFSET);
- putreg32(1 << pin, base + PIC32MX_IOPORT_ODCCLR_OFFSET);
+ putreg32(mask, base + PIC32MX_IOPORT_TRISSET_OFFSET);
+ putreg32(mask, base + PIC32MX_IOPORT_ODCCLR_OFFSET);
+
+ /* Is it an analog input? */
+
+#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+ if (pic32mx_analog(cfgset))
+ {
+ putreg32(mask, base + PIC32MX_IOPORT_ANSELSET_OFFSET);
+ }
+ else
+ {
+ putreg32(mask, base + PIC32MX_IOPORT_ANSELCLR_OFFSET);
+ }
+#endif
}
sched_unlock();
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h
index 7ba2d239f..0af09a40c 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h
@@ -59,7 +59,7 @@
/* GPIO settings used in the configport, readport, writeport, etc.
*
* General encoding:
- * MMxV IIDx RRRx PPPP
+ * MMAV IIDx RRRx PPPP
*/
#define GPIO_MODE_SHIFT (14) /* Bits 14-15: I/O mode */
@@ -68,6 +68,12 @@
# define GPIO_OUTPUT (2 << GPIO_MODE_SHIFT) /* 10 Normal output */
# define GPIO_OPENDRAN (3 << GPIO_MODE_SHIFT) /* 11 Open drain output */
+#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+#define GPIO_ANALOG_MASK (1 << 13) /* Bit 13: Analog */
+# define GPIO_ANALOG (1 << 13)
+# define GPIO_DIGITAL (0)
+#endif
+
#define GPIO_VALUE_MASK (1 << 12) /* Bit 12: Initial output value */
# define GPIO_VALUE_ONE (1 << 12)
# define GPIO_VALUE_ZERO (0)