Browse Source

SD card now works on the PIC32MX7 MMB board

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4799 7fd9a85b-ad96-42d3-883c-3090e2eb8679
sbg
patacongo 13 years ago
parent
commit
ad5395c160
  1. 7
      nuttx/ChangeLog
  2. 16
      nuttx/arch/mips/src/pic32mx/pic32mx-spi.c
  3. 32
      nuttx/configs/pic32mx7mmb/README.txt
  4. 4
      nuttx/configs/pic32mx7mmb/include/board.h
  5. 4
      nuttx/configs/pic32mx7mmb/nsh/defconfig
  6. 17
      nuttx/configs/pic32mx7mmb/src/up_nsh.c
  7. 2
      nuttx/configs/pic32mx7mmb/src/up_spi.c
  8. 6
      nuttx/drivers/mmcsd/mmcsd_spi.c
  9. 2
      nuttx/include/nuttx/spi.h

7
nuttx/ChangeLog

@ -2874,5 +2874,10 @@ @@ -2874,5 +2874,10 @@
the Mikroelektronika PIC32MX7 MMB board (not working on initial check-in).
* arch/mips/src/pic32/pic32mx-spi.c: Add support for very low-level,
register access debug output.
* configs//pic32mx7mmb/include/board.h: Reduced peripheral clock to
4MHz to match other PIC32 configurations.
* configs/pic32mx7mmb/src/up_nsh.c: SD card needs to operate in SPI
mode 2.
* configs/pic32mx7mmb/nsh/defconfig: MMC/SD card support is now
enabled by default in the PIC32MX7 MMB board configuration.

16
nuttx/arch/mips/src/pic32mx/pic32mx-spi.c

@ -64,7 +64,7 @@ @@ -64,7 +64,7 @@
* Definitions
****************************************************************************/
/* Enables non-standard debug output from this file.
*
*
* CONFIG_SPI_DEBUG && CONFIG_DEBUG - Define to enable basic SPI debug
* CONFIG_DEBUG_VERBOSE - Define to enable verbose SPI debug
*/
@ -527,7 +527,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) @@ -527,7 +527,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
}
/* Save the new BRG value */
spi_putreg(priv, PIC32MX_SPI_BRG_OFFSET, regval);
spivdbg("PBCLOCK: %d frequency: %d divisor: %d BRG: %d\n",
BOARD_PBCLOCK, frequency, divisor, regval);
@ -619,19 +619,19 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) @@ -619,19 +619,19 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
{
case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */
break;
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
regval |= SPI_CON_CKE;
break;
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
regval |= SPI_CON_CKP;
break;
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
regval |= (SPI_CON_CKP|SPI_CON_CKE);
break;
default:
DEBUGASSERT(FALSE);
return;
@ -866,7 +866,7 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw @@ -866,7 +866,7 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
while ((spi_getreg(priv, PIC32MX_SPI_STAT_OFFSET) & SPI_STAT_SPIRBF) == 0);
#endif
/* Read the received data from the SPI Data Register */
/* Read the received data from the SPI Data Register */
*ptr++ = (uint8_t)spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET);
nwords--;
@ -950,7 +950,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port) @@ -950,7 +950,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
/* Clear the receive buffer by reading from the BUF register */
regval = spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET);
#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS
/* Attach the interrupt vector. We do this early to make sure that the
* resource is available.

32
nuttx/configs/pic32mx7mmb/README.txt

@ -572,10 +572,17 @@ Where <subdir> is one of the following: @@ -572,10 +572,17 @@ Where <subdir> is one of the following:
The OS test produces all of its test output on the serial console.
This configuration has UART1 enabled as a serial console.
USB Configuations.
-----------------
SD Card Support
---------------
SD card support is built into this example by default:
CONFIG_PIC32MX_SPI1=y
CONFIG_NSH_ARCHINIT=y
USB Configurations.
------------------
Several USB device configurations can be enabled and included
as NSH built-in built in functions.
as NSH built-in built in functions. USB is *not* enabled by default.
To use USB device, connect the starter kit to the host using a cable
with a Type-B micro-plug to the starter kit’s micro-A/B port J5, located
@ -612,11 +619,9 @@ Where <subdir> is one of the following: @@ -612,11 +619,9 @@ Where <subdir> is one of the following:
to enable the USB mass storage device. However, this device cannot
work until support for the SD card is also incorporated.
Networking Configuations.
-------------------------
Several Networking configurations can be enabled and included
as NSH built-in built in functions. The following additional
configuration settings are required:
Networking Configurations.
--------------------------
Networking is enabled by default in this configuration:
CONFIG_NET=y : Enable networking support
CONFIG_PIC32MX_ETHERNET=y : Enable the PIC32 Ethernet driver
@ -628,6 +633,8 @@ Where <subdir> is one of the following: @@ -628,6 +633,8 @@ Where <subdir> is one of the following:
CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) : Target IP address 10.0.0.2
CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host IP address 10.0.0.1
This will probably need to be customized for your network.
NOTES:
1. This logic will assume that a network is connected. During its
initialization, it will try to negotiate the link speed. If you have
@ -636,19 +643,14 @@ Where <subdir> is one of the following: @@ -636,19 +643,14 @@ Where <subdir> is one of the following:
before the networking finally gives up and decides that no network is
available.
2. To add SPI-based support for the SD card slot:
CONFIG_PIC32MX_SPI1=y
CONFIG_NSH_ARCHINIT=y
3. This example can support an FTP client. In order to build in FTP client
2. This example can support an FTP client. In order to build in FTP client
support simply uncomment the following lines in the appconfig file (before
configuring) or in the apps/.config file (after configuring):
#CONFIGURED_APPS += netutils/ftpc
#CONFIGURED_APPS += examples/ftpc
4. This example can support an FTP server. In order to build in FTP server
3. This example can support an FTP server. In order to build in FTP server
support simply uncomment the following lines in the appconfig file (before
configuring) or in the apps/.config file (after configuring):

4
nuttx/configs/pic32mx7mmb/include/board.h

@ -87,8 +87,8 @@ @@ -87,8 +87,8 @@
* PBCLOCK = CPU_CLOCK / PBDIV
*/
#define BOARD_PBDIV 1 /* Peripheral clock divisor (PBDIV) */
#define BOARD_PBCLOCK 80000000 /* Peripheral clock (PBCLK = 80MHz/1) */
#define BOARD_PBDIV 2 /* Peripheral clock divisor (PBDIV) */
#define BOARD_PBCLOCK 40000000 /* Peripheral clock (PBCLK = 80MHz/2) */
/* Watchdog pre-scaler (re-visit) */

4
nuttx/configs/pic32mx7mmb/nsh/defconfig

@ -140,7 +140,7 @@ CONFIG_PIC32MX_OC4=n @@ -140,7 +140,7 @@ CONFIG_PIC32MX_OC4=n
CONFIG_PIC32MX_OC5=n
CONFIG_PIC32MX_I2C1=n
CONFIG_PIC32MX_I2C2=n
CONFIG_PIC32MX_SPI1=n
CONFIG_PIC32MX_SPI1=y
CONFIG_PIC32MX_SPI2=n
CONFIG_PIC32MX_SPI3=n
CONFIG_PIC32MX_SPI4=n
@ -1330,7 +1330,7 @@ CONFIG_NSH_ROMFSETC=n @@ -1330,7 +1330,7 @@ CONFIG_NSH_ROMFSETC=n
CONFIG_NSH_CONSOLE=y
#CONFIG_NSH_CONDEV="/dev/ttyS1"
CONFIG_NSH_TELNET=n
CONFIG_NSH_ARCHINIT=n
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
CONFIG_NSH_NOMAC=n

17
nuttx/configs/pic32mx7mmb/src/up_nsh.c

@ -229,13 +229,13 @@ static int nsh_waiter(int argc, char *argv[]) @@ -229,13 +229,13 @@ static int nsh_waiter(int argc, char *argv[])
#ifdef CONFIG_NSH_HAVEMMCSD
static int nsh_sdinitialize(void)
{
FAR struct spi_dev_s *ssp;
FAR struct spi_dev_s *spi;
int ret;
/* Get the SPI port */
ssp = up_spiinitialize(CONFIG_NSH_MMCSDSPIPORTNO);
if (!ssp)
spi = up_spiinitialize(CONFIG_NSH_MMCSDSPIPORTNO);
if (!spi)
{
message("nsh_archinitialize: Failed to initialize SPI port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
@ -246,10 +246,19 @@ static int nsh_sdinitialize(void) @@ -246,10 +246,19 @@ static int nsh_sdinitialize(void)
message("Successfully initialized SPI port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
/* The SPI should be in 8-bit (default) and mode2: CKP=1, CKE=0.
* The MMC/SD driver will control the SPI frequency. WARNING:
* this is not the right way to do this... this should be done
* the MMC/SD driver: Other device on SPI1 may need other mode
* settings.
*/
SPI_SETMODE(spi, SPIDEV_MODE2);
/* Bind the SPI port to the slot */
ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR,
CONFIG_NSH_MMCSDSLOTNO, ssp);
CONFIG_NSH_MMCSDSLOTNO, spi);
if (ret < 0)
{
message("nsh_sdinitialize: "

2
nuttx/configs/pic32mx7mmb/src/up_spi.c

@ -127,7 +127,7 @@ void weak_function pic32mx_spiinitialize(void) @@ -127,7 +127,7 @@ void weak_function pic32mx_spiinitialize(void)
* including up_spiinitialize()) are provided by common PIC32MX logic. To use
* this common SPI logic on your board:
*
* 1. Provide logic in pic32mx_boardinitialize() to configure SPI/SSP chip select
* 1. Provide logic in pic32mx_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide pic32mx_spiNselect() and pic32mx_spiNstatus() functions
* in your board-specific logic. These functions will perform chip selection

6
nuttx/drivers/mmcsd/mmcsd_spi.c

@ -622,7 +622,7 @@ static uint32_t mmcsd_taac(FAR struct mmcsd_slot_s *slot, uint8_t *csd) @@ -622,7 +622,7 @@ static uint32_t mmcsd_taac(FAR struct mmcsd_slot_s *slot, uint8_t *csd)
/****************************************************************************
* Name: mmcsd_decodecsd
*
* Description:
* Description:
*
****************************************************************************/
@ -1013,7 +1013,7 @@ static int mmcsd_open(FAR struct inode *inode) @@ -1013,7 +1013,7 @@ static int mmcsd_open(FAR struct inode *inode)
}
}
/* Make sure that the card is ready */
/* Make sure that the card is ready */
SPI_SELECT(spi, SPIDEV_MMCSD, true);
ret = mmcsd_waitready(slot);
@ -1706,7 +1706,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) @@ -1706,7 +1706,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
* exceeds 4096 x 512, then we must be dealing with a card with read_bl_len
* of 1024 or 2048.
*/
if (!IS_SDV2(slot->type) && slot->nsectors <= ((uint32_t)4096*12))
{
/* Don't set the block len on high capacity cards (ver1.x or ver2.x) */

2
nuttx/include/nuttx/spi.h

@ -132,7 +132,7 @@ @@ -132,7 +132,7 @@
* Name: SPI_SETMODE
*
* Description:
* Set the SPI mode. Optional. See enum spi_mode_e for mode definitions
* Set the SPI mode. Optional. See enum spi_mode_e for mode definitions.
*
* Input Parameters:
* dev - Device-specific state data

Loading…
Cancel
Save