summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttX.html6
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html34
-rw-r--r--nuttx/configs/sure-pic32mx/README.txt100
-rw-r--r--nuttx/configs/sure-pic32mx/include/board.h13
-rw-r--r--nuttx/configs/sure-pic32mx/src/Makefile5
-rw-r--r--nuttx/configs/sure-pic32mx/src/up_buttons.c21
-rw-r--r--nuttx/configs/sure-pic32mx/src/up_spi.c100
-rw-r--r--nuttx/configs/sure-pic32mx/src/up_usbdev.c15
9 files changed, 266 insertions, 30 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 3a8eb9660..ef454be6c 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2552,3 +2552,5 @@
6.17 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+ * configs/sure-pic32mx: Add support for the Sure DB-DP11212 PIC32 General
+ Purpose Demo Board
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index e49e50f48..2920d4643 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: March 10, 2012</p>
+ <p>Last Updated: March 11, 2012</p>
</td>
</tr>
</table>
@@ -478,7 +478,7 @@
<td>
<p>
<li>
- Network, USB (host), USB (device), serial, CAN, ADC, DAC, and PWM driver architectures.
+ Network, USB (host), USB (device), serial, CAN, ADC, DAC, PWM, and Quadrature Encoder driver architectures.
</li>
</p>
</tr>
@@ -1790,7 +1790,7 @@
<a href="http://www.nuttx.org/NuttShell.html">NSH User Guide</a>) as well as several other configurations.
Additional drivers and configurations were added in NuttX 6.13-6.16.
Drivers include an Ethernet driver, ADC driver, DAC driver, PWM driver, CAN driver, F4 RTC driver, Quadrature Encoder, DMA, SDIO with DMA
- (most of these are compatible with the F1 family as well).
+ (these should all be compatible with the STM32 F2 family and many should also be compatible with the STM32 F1 family as well).
The NuttX6.16 release also includes and logic for saving/restoring F4 FPU registers in context switches.
Networking intensions include support for Telnet NSH sessions and new configurations for DHPCD and the networking test (nettest).
A more complete port would include support for SDIO and USB OTG which are not available in NuttX 6.13.
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index f99cf45ad..e92025862 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
- <p>Last Updated: March 3, 2011</p>
+ <p>Last Updated: March 11, 2011</p>
</td>
</tr>
</table>
@@ -128,7 +128,8 @@
<a href="#usbdevdrivers">6.3.10 USB Device-Side Drivers</a><br>
<a href="#analogdrivers">6.3.11 Analog (ADC/DAC) Drivers</a><br>
<a href="#pwmdrivers">6.3.12 PWM Drivers</a><br>
- <a href="#candrivers">6.3.13 CAN Drivers</a>
+ <a href="#candrivers">6.3.13 CAN Drivers</a><br>
+ <a href="#quadencoder">6.3.14 Quadrature Encoder Drivers</a>
</ul>
<a href="#pwrmgmt">6.4 Power Management</a>
<ul>
@@ -3258,6 +3259,35 @@ extern void up_ledoff(int led);
</li>
</ul>
+<h3><a name="quadencoder">6.3.14 Quadrature Encoder Drivers</a></h3>
+<p>
+ NuttX supports only a low-level, two-part Quadrature Driver driver.
+</p>
+<ol>
+ <li>
+ An &quot;upper half&quot;, generic driver that provides the comman Quadrature Encoder interface to application level code, and
+ </li>
+ <li>
+ A &quot;lower half&quot;, platform-specific driver that implements the low-level timer controls to implement the Quadrature Encoder functionality.
+ </li>
+</ol>
+<p>
+ Files supporting the Quadrature Encoder can be found in the following locations:
+</p>
+<ul>
+ <li><b>Interface Definition</b>.
+ The header file for the NuttX Quadrature Encoder driver reside at <code>include/nuttx/sensors/qencoder.h</code>.
+ This header file includes both the application level interface to the Quadrature Encoder driver as well as the interface between the &quot;upper half&quot; and &quot;lower half&quot; drivers.
+ The Quadrature Encoder module uses a standard character driver framework.
+ </li>
+ <li><b>&quot;Upper Half&quot; Driver</b>.
+ The generic, &quot;upper half&quot; Quadrature Encoder driver resides at <code>drivers/sensors/qencoder.c</code>.
+ </li>
+ <li><b>&quot;Lower Half&quot; Drivers</b>.
+ Platform-specific Quadrature Encoder drivers reside in <code>arch/</code><i>&lt;architecture&gt;</i><code>/src/</code><i>&lt;chip&gt;</i> directory for the specific processor <i>&lt;architecture&gt;</i> and for the specific <i>&lt;chip&gt;</i> Quadrature Encoder peripheral devices.
+ </li>
+</ul>
+
<h2><a name="pwrmgmt">6.4 Power Management</a></h2>
<h3><a name="pmoverview">6.4.1 Overview</a></h3>
diff --git a/nuttx/configs/sure-pic32mx/README.txt b/nuttx/configs/sure-pic32mx/README.txt
index e21325984..c7ba540bb 100644
--- a/nuttx/configs/sure-pic32mx/README.txt
+++ b/nuttx/configs/sure-pic32mx/README.txt
@@ -42,7 +42,10 @@ Contents
PIC32MX440F512H Pin Out
=======================
- PIC32MX440F512H 64-Pin QFN (USB) Pin Out.
+ DB_DP11215 PIC32 Storage Demo Board
+ -----------------------------------
+ PIC32MX440F512H 64-Pin QFN (USB) Pin Out as used on the DB_DP11215 PIC32 Storage
+ Demo Board.
LEFT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
PIN NAME SIGNAL NOTES
@@ -65,7 +68,8 @@ PIC32MX440F512H Pin Out
RB1
16 PGED1/AN0/VREF+/CVREF+/PMA6/ N/C Not connected
CN2/RB0
- *FLASH (U1, SOIOC) not populated
+
+ *FLASH (U1, SOIC) not populated
BOTTOM SIDE, LEFT-TO-RIGHT (if pin 1 is in upper left)
PIN NAME SIGNAL NOTES
@@ -88,7 +92,7 @@ PIC32MX440F512H Pin Out
31 SDA2/U2RX/PMA9/CN17/RF4 RXD2_MCU J5 DB9 via RS232 driver
32 SCL2/U2TX/PMA8/CN18/RF5 TXD2_MCU J5 DB9 via RS232 driver
- *FLASH (U1, SOIOC) not populated
+ *FLASH (U1, SOIC) not populated
RIGHT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
PIN NAME SIGNAL NOTES
@@ -133,6 +137,96 @@ PIC32MX440F512H Pin Out
*USB-to-UART bridge (U1, CP2102) not populated
+ DB-DP11212 PIC32 General Purpose Demo Board
+ -------------------------------------------
+ PIC32MX440F512H 64-Pin QFN (USB) Pin Out as used on the DB-DP11212 PIC32 General
+ Purpose Demo Board
+
+ LEFT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
+ PIN NAME SIGNAL NOTES
+ ---- ----------------------------- -------------- -------------------------------
+ 1 PMD5/RE5 PMPD5 Display, JP1-12, DB5
+ 2 PMD6/RE6 PMPD6 Display, JP1-13, DB6
+ 3 PMD7/RE7 PMPD7 Display, JP1-14, DB7
+ 4 SCK2/PMA5/CN8/RG6 SCK FLASH (U4) SCK*
+ 5 SDI2/PMA4/CN9/RG7 SDI FLASH (U4) SO*
+ 6 SDO2/PMA3/CN10/RG8 SDO FLASH (U4) SI*
+ 7 MCLR\ PIC_MCLR Pulled high, J2-1, ICSP
+ 8 SS2/PMA2/CN11/RG9 N/C Not connected
+ 9 Vss Grounded
+ 10 Vdd +3.3V ---
+ 11 Vbuson/AN5/CN7/RB5 RB5 LCD SEG5 (F), U5-10
+ 12 AN4/CN6/RB4 RB4 LCD SEG4 (E), U5-1
+ 13 AN3/CN5/RB3 RB3 LCD SEG3 (D), U5-2
+ 14 AN2/CN4/RB2 RB2 LCD SEG2 (C), U5-4
+ 15 PGEC1/AN1/Vref-/CN3/RB1 RB1 LCD SEG1 (B), U5-7
+ 16 PGED1/AN0/VREF+/CVREF+/PMA6/ RB0 LCD SEG0 (A), U5-11
+ CN2/RB0
+
+ *FLASH (U4, SOIC) not populated
+
+ BOTTOM SIDE, LEFT-TO-RIGHT (if pin 1 is in upper left)
+ PIN NAME SIGNAL NOTES
+ ---- ----------------------------- -------------- -------------------------------
+ 17 PGEC2/AN6/OCFA/RB6 PIC_PGC2 J2-5, ICSP
+ 18 PGED2/AN7/RB7 PIC_PGD2 J2-4, ICSP
+ 19 AVdd +3.3V ---
+ 20 AVss Grounded
+ 21 AN8/U2CTS/RB8 RB8 LCD SEG6 (G), U5-5
+ 22 AN9/PMA7/RB9 RB9 LCD SEG7 (DP), U5-3
+ 23 TMS/AN10/PMA13/RB10 UTIL_WP FLASH (U4) WP*
+ 24 TDO/AN11/PMA12/RB11 UTIL_CS FLASH (U4) CS*
+ 25 Vss Grounded
+ 26 Vdd +3.3V ---
+ 27 TCK/AN12/PMA11/RB12 N/C Not connected
+ 28 TDI/AN13/PMA10/RB13 N/C Not connected
+ 29 AN14/U2RTS/PMA1/RB14 temp_AD temp_AD
+ 30 AN15/PMA0/CN12/RB15 PMPA0 Display, JP1-4, RS
+ 31 SDA2/U2RX/PMA9/CN17/RF4 SDA LM75/SO, U3-1, SDA
+ 32 SCL2/U2TX/PMA8/CN18/RF5 SCL LM75/SO, U3-2, SCL
+
+ *FLASH (U4, SOIC) not populated
+
+ RIGHT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
+ PIN NAME SIGNAL NOTES
+ ---- ----------------------------- -------------- -------------------------------
+ 48 SOSCO/T1CK/CN0/RC14 SOSCO 32.768KHz XTAL (Y1)
+ 47 SOSCI/CN1/RC13 SOSCI 32.768KHz XTAL (Y1)
+ 46 OC1/INT0/RD0 RD0 LCD DIG1, U5-12
+ 45 IC4/PMCS1/PMA14/RD11 PMCS1 Display, JP1-6, E
+ 44 SCL1/PMCS2/PMA15 RD10 LCD DIG2, U5-9
+ 43 SDA1/RD9 RD9 LCD DIG3, U5-8
+ 42 RTCC/RD8 RD8 LCD DIG4, U5-6
+ 41 Vss Grounded
+ 40 OSC2/CLKO/RC15 OSC2 20MHz XTAL (Y2)
+ 39 OSC1/CLKI/RC12 OSC1 20MHz XTAL (Y2)
+ 38 Vdd +3.3V ---
+ 37 D+ MCU_D+ USB connectors via PHY
+ 36 D- MCU_D- USB connectors via PHY
+ 35 Vusb +3.3V ---
+ 34 Vbus +5V_DUSB Display, USB Mini-B, USB Type A, JP1-1, +5V
+ 33 USBID/RF3 N/C Not connected
+
+ TOP SIDE, LEFT-TO-RIGHT (if pin 1 is in upper left)
+ PIN NAME SIGNAL NOTES
+ ---- ----------------------------- -------------- -------------------------------
+ 64 PMPD4/RD4 PMPD4 Display, JP1-11, DB4
+ 63 PMPD3/RD3 PMPD3 Display, JP1-10, DB3
+ 62 PMPD2/RD2 PMPD2 Display, JP1-9, DB2
+ 61 PMPD1/RD1 PMPD1 Display, JP1-8, DB1
+ 60 PMPD0/RE0 PMPD0 Display, JP1-7, DB0
+ 59 RF1 Key3 SW3-1
+ 58 RF0 Key2 SW2-1
+ 57 ENVREG ENVREG Pulled high
+ 56 Vcap/Vddcore VDDCORE Capacitors to ground
+ 55 CN16/RD7 N/C Not connected
+ 54 CN15/RD6 Key5 SW5-1
+ 53 PMRD/CN14/RD5 PMPRD ---
+ 52 OC5/PMWR/CN13/RD4 PWM2 Used to control backlight level (Vo)
+ 51 U1TX/OC4/RD3 N/C Not connected
+ 50 U1RX/OC3/RD2 N/C Not connected
+ 49 OC2/RD1 PWM1 Used to control backlight level (K)
+
Toolchains
==========
diff --git a/nuttx/configs/sure-pic32mx/include/board.h b/nuttx/configs/sure-pic32mx/include/board.h
index 44eff5b62..66ed642c6 100644
--- a/nuttx/configs/sure-pic32mx/include/board.h
+++ b/nuttx/configs/sure-pic32mx/include/board.h
@@ -2,7 +2,7 @@
* configs/sure-pic32mx/include/board.h
* include/arch/board/board.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -91,8 +91,9 @@
#undef BOARD_TIMER1_SOSC
/* LED definitions **********************************************************/
-/* The Sure PIC32MX board has five LEDs. One (D4, lablel "Power") is not
- * controllable by software. Four are controllable by software:
+/* The Sure DB_DP11215 PIC32 Storage Demo Board board has five LEDs. One
+ * (D4, lablel "Power") is not controllable by software. Four are
+ * controllable by software:
*
* D7 "USB" Yellow RD7 Low illuminates
* D8 "SD" Yellow RD6 Low illuminates
@@ -111,6 +112,12 @@
#define LED_PANIC 5 /* N/C N/C N/C ON N/C N/C N/C OFF */
#define LED_NVALUES 6
+/* The Sure DB-DP11212 PIC32 General Purpose Demo Board does not have any user
+ * controllable LEDs, but does does have a segment LED display. That display is
+ * however, obscured by the larger segment display attached to the board and, so,
+ * is not supported.
+ */
+
/* For distinguishing individual LEDs */
#define LED_USB 0
diff --git a/nuttx/configs/sure-pic32mx/src/Makefile b/nuttx/configs/sure-pic32mx/src/Makefile
index f934ae35a..f5f9a89ea 100644
--- a/nuttx/configs/sure-pic32mx/src/Makefile
+++ b/nuttx/configs/sure-pic32mx/src/Makefile
@@ -40,9 +40,14 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
CSRCS = up_boot.c up_spi.c
+# Only the DB_DP11215 PIC32 Storage Demo Board board has user controllable
+# LEDs
+
+ifeq ($(CONFIG_ARCH_DBDP11215),y)
ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS += up_leds.c
endif
+endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
diff --git a/nuttx/configs/sure-pic32mx/src/up_buttons.c b/nuttx/configs/sure-pic32mx/src/up_buttons.c
index 9fccedfc1..80fb35fdb 100644
--- a/nuttx/configs/sure-pic32mx/src/up_buttons.c
+++ b/nuttx/configs/sure-pic32mx/src/up_buttons.c
@@ -58,20 +58,33 @@
/****************************************************************************
* Definitions
****************************************************************************/
-/* The Sure PIC32MX board has three buttons.
+/* The Sure DB_DP11215 PIC32 Storage Demo Board has three buttons.
*
* SW1 (SW_UP, left arrow) RB3 Pulled high, Grounded/low when depressed
* SW2 (SW_DOWN, down/right arrow) RB2 Pulled high, Grounded/low when depressed
* SW3 (SW_OK, right arrow) RB4 Pulled high, Grounded/low when depressed
*
+ * The Sure DB-DP11212 PIC32 General Purpose Demo Board also has three buttons,
+ * but these are connected differently:
+ *
+ * SW2-1 RF0 Pulled high, Grounded/low when depressed
+ * SW3-1 RF1 Pulled high, Grounded/low when depressed
+ * SW5-1 RD6 Pulled high, Grounded/low when depressed
+ *
* Internal pull-ups are not required since the LEDs are pull-up externally.
* Change notification interrupts are not *automatically* enabled. Change
* notification will be enabled when pic32mx_gpioattach() is called.
*/
-#define GPIO_SW1 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN3)
-#define GPIO_SW2 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN2)
-#define GPIO_SW3 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN4)
+#ifdef CONFIG_ARCH_DBDP11215
+# define GPIO_SW1 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_SW2 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN2)
+# define GPIO_SW3 (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN4)
+#else /* CONFIG_ARCH_DBDP11212 */
+# define GPIO_SW1 (GPIO_INPUT|GPIO_INT|GPIO_PORTF|GPIO_PIN0)
+# define GPIO_SW2 (GPIO_INPUT|GPIO_INT|GPIO_PORTF|GPIO_PIN1)
+# define GPIO_SW3 (GPIO_INPUT|GPIO_INT|GPIO_PORTD|GPIO_PIN6)
+#endif
/* Change notification numbers:
* RB3 -> CN5
diff --git a/nuttx/configs/sure-pic32mx/src/up_spi.c b/nuttx/configs/sure-pic32mx/src/up_spi.c
index 36ba0844d..02ffa4f48 100644
--- a/nuttx/configs/sure-pic32mx/src/up_spi.c
+++ b/nuttx/configs/sure-pic32mx/src/up_spi.c
@@ -57,9 +57,11 @@
/************************************************************************************
* Definitions
************************************************************************************/
-/* The Sure PIC32MX has an SD slot connected on SPI2:
+
+#ifdef CONFIG_ARCH_DBDP11215
+
+/* The Sure DB_DP11215 PIC32 Storage Demo Board has an SD slot connected on SPI2:
*
- * SPI
* SCK2/PMA5/CN8/RG6 SCK SD connector SCK, FLASH (U1) SCK*
* SDI2/PMA4/CN9/RG7 SDI SD connector DO, FLASH (U1) SO*
* SDO2/PMA3/CN10/RG8 SDO SD connector DI, FLASH (U1) SI*
@@ -73,12 +75,51 @@
* TDI/AN13/PMA10/RB13 SD_WD SD connector WD
*/
-#define GPIO_SD_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN11)
-#define GPIO_SD_CD (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_SD_WD (GPIO_INPUT|GPIO_PORTB|GPIO_PIN13)
+# define PIC32_HAVE_SD 1
+
+# define GPIO_SD_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN11)
+# define GPIO_SD_CD (GPIO_INPUT|GPIO_INT|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_SD_WD (GPIO_INPUT|GPIO_PORTB|GPIO_PIN13)
+
+/* The Sure DB_DP11215 PIC32 Storage Demo Board has pads an SOIC (Flash or
+ * EEPROM) connected on SPI2, however, U4 is not populated on my board.
+ *
+ *
+ * TMS/AN10/CVREFOUT/PMA13/RB10 UTIL_WP FLASH (U1) WP
+ * SS2/PMA2/CN11/RG9 UTIL_CS FLASH (U1) CS
+ */
+
+# undef PIC32_HAVE_SOIC
+# define GPIO_SOIC_WP (GPIO_INPUT|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_SOIC_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTG|GPIO_PIN0)
+
/* Change notification numbers -- Not available for SD_CD. */
+#endif
+
+#ifdef CONFIG_ARCH_DBDP11212
+
+/* The Sure DB-DP11212 PIC32 General Purpose Demo Board does not have an
+ * SD slot.
+ */
+
+# undef PIC32_HAVE_SD
+
+ /* The Sure DB-DP11212 PIC32 General Purpose Demo Board has an SOIC (Flash or
+ * EEPROM) connected on SPI2:
+ *
+ *
+ * TMS/AN10/PMA13/RB10 UTIL_WP FLASH (U4) WP
+ * TDO/AN11/PMA12/RB11 UTIL_CS FLASH (U4) CS
+ */
+
+# define PIC32_HAVE_SOIC 1
+
+# define GPIO_SOIC_WP (GPIO_INPUT|GPIO_PORTB|GPIO_PIN10)
+# define GPIO_SOIC_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN11)
+#endif
+
/* The following enable debug output from this file.
*
* CONFIG_DEBUG_SPI && CONFIG_DEBUG - Define to enable basic SPI debug
@@ -124,9 +165,16 @@ void weak_function pic32mx_spiinitialize(void)
* write protect (WP) inputs.
*/
+#ifdef PIC32_HAVE_SD
pic32mx_configgpio(GPIO_SD_CS);
pic32mx_configgpio(GPIO_SD_CD);
pic32mx_configgpio(GPIO_SD_WD);
+#endif
+
+#ifdef PIC32_HAVE_SOIC
+ pic32mx_configgpio(GPIO_SOIC_WP);
+ pic32mx_configgpio(GPIO_SOIC_CS);
+#endif
}
/************************************************************************************
@@ -161,32 +209,62 @@ void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool se
/* The SD card chip select is pulled high and active low */
+#ifdef PIC32_HAVE_SD
if (devid == SPIDEV_MMCSD)
{
pic32mx_gpiowrite(GPIO_SD_CS, !selected);
}
+#endif
+
+#ifdef PIC32_HAVE_SOIC
+ if (devid == SPIDEV_FLASH)
+ {
+ pic32mx_gpiowrite(GPIO_SOIC_CS, !selected);
+ }
+#endif
}
uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
uint8_t ret = 0;
- /* Card detect is pull up on-board. If a low value is sensed then the card must
- * be present.
+ /* Card detect is pull up on-board. If a low value is sensed then the
+ * card must be present.
*/
- if (!pic32mx_gpioread(GPIO_SD_CD))
+#ifdef PIC32_HAVE_SD
+ if (devid == SPIDEV_MMCSD)
+ {
+ if (!pic32mx_gpioread(GPIO_SD_CD))
+ {
+ ret = SPI_STATUS_PRESENT;
+
+ /* It seems that a high value indicates the the card is write
+ * protected.
+ */
+
+ if (pic32mx_gpioread(GPIO_SD_WD))
+ {
+ ret |= SPI_STATUS_WRPROTECTED;
+ }
+ }
+ }
+#endif
+
+#ifdef PIC32_HAVE_SOIC
+ if (devid == SPIDEV_FLASH)
{
ret = SPI_STATUS_PRESENT;
- /* It seems that a high value indicatest the the card is write protected. */
+ /* Write protect is indicated with a low value. */
- if (pic32mx_gpioread(GPIO_SD_WD))
+ if (pic32mx_gpioread(GPIO_SOIC_WP))
{
ret |= SPI_STATUS_WRPROTECTED;
}
}
-
+#endif
+
spivdbg("Returning %d\n", ret);
return ret;
}
diff --git a/nuttx/configs/sure-pic32mx/src/up_usbdev.c b/nuttx/configs/sure-pic32mx/src/up_usbdev.c
index 667bd1837..bb175f664 100644
--- a/nuttx/configs/sure-pic32mx/src/up_usbdev.c
+++ b/nuttx/configs/sure-pic32mx/src/up_usbdev.c
@@ -56,7 +56,10 @@
/************************************************************************************
* Definitions
************************************************************************************/
-/*
+/* The Sure DB_DP11215 PIC32 Storage Demo Board has a CP2102 PHY that is shared
+ * between the USB and the UART-to-USB logic. That PHY must be programmed during
+ * boot up for USB functionality (since the UART-to-USB is not populated).
+ *
* PIN NAME SIGNAL NOTES
* ---- ------------------------------- -------------- ------------------------------
* 11 AN5/C1IN+/Vbuson/CN7/RB5 Vbuson/AN5/RB5 To USB VBUS circuitry
@@ -64,9 +67,11 @@
* 44 SCL1/IC3/PMCS2/PMA15/INT3/RD10 USB_OPT USB PHY
*/
-#define GPIO_USB_VBUSON (GPIO_INPUT|GPIO_PORTB|GPIO_PIN5)
-#define GPIO_USB_OPTEN (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN9)
-#define GPIO_USB_OPT (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTD|GPIO_PIN10)
+#ifdef CONFIG_ARCH_DBDP11215
+# define GPIO_USB_VBUSON (GPIO_INPUT|GPIO_PORTB|GPIO_PIN5)
+# define GPIO_USB_OPTEN (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN9)
+# define GPIO_USB_OPT (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTD|GPIO_PIN10)
+#endif
/************************************************************************************
* Private Functions
@@ -88,8 +93,10 @@ void weak_function pic32mx_usbdevinitialize(void)
{
/* Connect the PHY to the USB mini-B port. Order and timing matter! */
+#ifdef CONFIG_ARCH_DBDP11215
pic32mx_configgpio(GPIO_USB_OPTEN);
pic32mx_configgpio(GPIO_USB_OPT);
+#endif
/* Notes from the Sure Electronics sample code:
*