Updates for PIC32MX USB driver

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4233 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2011-12-27 20:07:17 +00:00
parent 50eddba2ce
commit 269fd5a9cc
9 changed files with 408 additions and 331 deletions

View File

@ -2300,3 +2300,6 @@
6.14 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
* tools/Makefile.txport, mkexport.sh, and configure.sh. Changes submitted
by Mike Smith to support configuration and 'make export' on MAC OS.

View File

@ -1,4 +1,4 @@
NuttX TODO List (Last updated December 20, 2011)
NuttX TODO List (Last updated December 27, 2011)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@ -31,7 +31,7 @@ nuttx/
(2) ARM/LPC313x (arch/arm/src/lpc313x/)
(3) ARM/STR71x (arch/arm/src/str71x/)
(3) ARM/LM3S6918 (arch/arm/src/lm3s/)
(4) ARM/STM32 (arch/arm/src/stm32/)
(5) ARM/STM32 (arch/arm/src/stm32/)
(3) AVR (arch/avr)
(0) Intel x86 (arch/x86)
(4) 8051 / MCS51 (arch/8051/)
@ -1072,6 +1072,12 @@ o ARM/STM32 (arch/arm/src/stm32/)
Priority: Low until someone needs DMA1, Channel 5 (ADC3, UART4_TX, TIM5_CH1, or
TIM8_CH2).
Title: UNFINISHED DRIVERS
Description: The following drivers are incomplete: DAC. The following drivers
are untested: DMA on the F4, CAN.
Status: Open
Priority: Medium
o AVR (arch/avr)
^^^^^^^^^^^^^^

View File

@ -57,7 +57,7 @@
/* GPIO settings used in the configport, readport, writeport, etc.
*
* General encoding:
* MMxV Ixxx RRRx PPPP
* MMxV IIxx RRRx PPPP
*/
#define GPIO_MODE_SHIFT (14) /* Bits 14-15: I/O mode */
@ -70,7 +70,7 @@
# define GPIO_VALUE_ONE (1 << 12)
# define GPIO_VALUE_ZERO (0)
#define GPIO_INT_SHIFT (14) /* Bits 10-11: Interrupt mode */
#define GPIO_INT_SHIFT (10) /* Bits 10-11: Interrupt mode */
#define GPIO_INT_MASK (3 << GPIO_INT_SHIFT)
# define GPIO_INT_NONE (0 << GPIO_INT_SHIFT) /* Bit 00: No interrupt */
# define GPIO_INT (1 << GPIO_INT_SHIFT) /* Bit 01: Change notification enable */

View File

@ -70,7 +70,7 @@
#define PIC32MX_USB_BDTP3_OFFSET 0x02d0 /* USB Buffer Descriptor Table Pointer Register 3 */
#define PIC32MX_USB_CNFG1_OFFSET 0x02e0 /* USB Debug and Idle Register */
#define PIC32MX_USB_EP_OFFSET(n) 0x0300 /* USB Endpoint n Control Register */
#define PIC32MX_USB_EP_OFFSET(n) (0x0300+((n)<<4))
#define PIC32MX_USB_EP0_OFFSET 0x0300 /* USB Endpoint 0 Control Register */
#define PIC32MX_USB_EP1_OFFSET 0x0310 /* USB Endpoint 1 Control Register */
#define PIC32MX_USB_EP2_OFFSET 0x0320 /* USB Endpoint 2 Control Register */
@ -184,6 +184,8 @@
#define USB_INT_ATTACH (1 << 6) /* Bit 6: Peripheral Attach Interrupt */
#define USB_INT_STALL (1 << 7) /* Bit 7: STALL Handshake Interrupt */
#define USB_INT_ALL 0xff
/* USB Pending Error Interrupt Register */
/* USB Interrupt Error Enable Register */
@ -197,6 +199,8 @@
#define USB_EINT_BMX (1 << 6) /* Bit 6: Bus Matrix Error Flag */
#define USB_EINT_BTS (1 << 7) /* Bit 7: Bit Stuff Error Flag */
#define USB_EINT_ALL 0xff
/* USB Status FIFO Register */
#define USB_STAT_PPBI (1 << 2) /* Bit 2: Ping-Pong BD Pointer Indicator */
@ -277,18 +281,51 @@
#define USB_EP_EPHSHK (1 << 0) /* Bit 0: Endpoint Handshake Enable */
#define USB_EP_EPSTALL (1 << 1) /* Bit 1: Endpoint Stall Status */
#define USB_EP_EPRXEN (1 << 3) /* Bit 3: Endpoint Receive Enable */
#define USB_EP_EPTXEN (1 << 2) /* Bit 2: Endpoint Transmit Enable */
#define USB_EP_EPRXEN (1 << 3) /* Bit 3: Endpoint Receive Enable */
#define USB_EP_EPCONDIS (1 << 4) /* Bit 4: Bidirectional Endpoint Control */
#define USB_EP_RETRYDIS (1 << 6) /* Bit 6: Retry Disable (Host mode and U1EP0 only) */
#define USB_EP_LSPD (1 << 7) /* Bit 7: Low-Speed Direct Connection Enable */
/* Buffer Descriptor Table (BDT) ****************************************************/
/* Offset 0: On write (software->hardware) */
#define USB_BDT_BSTALL (1 << 2) /* Bit 2: Buffer Stall Enable bit */
#define USB_BDT_DTS (1 << 3) /* Bit 3: Data Toggle Synchronization Enable bit */
#define USB_BDT_NINC (1 << 4) /* Bit 4: DMA Address Increment Disable bit */
#define USB_BDT_KEEP (1 << 5) /* Bit 5: BD Keep Enable bit */
#define USB_BDT_DATA01 (1 << 6) /* Bit 6: Data Toggle Packet bit */
#define USB_BDT_UOWN (1 << 7) /* Bit 7: USB Own bit */
#define USB_BDT_BYTECOUNT_SHIFT (16) /* Bits 16-25: Byte Count bits */
#define USB_BDT_BYTECOUNT_MASK (0x3ff << USB_BDT_BYTECOUNT_SHIFT)
#define USB_BDT_DATA0 0 /* DATA0 packet expected next */
#define USB_BDT_DATA1 USB_BDT_DATA01 /* DATA1 packet expected next */
#define USB_BDT_COWN 0 /* CPU owns the descriptor */
/* Offset 0: On read (hardware->software) */
#define USB_BDT_PID_SHIFT (2) /* Bits 2-5: Packet Identifier bits */
#define USB_BDT_PID_MASK (15 << USB_BDT_BYTECOUNT_SHIFT)
/* Bit 7: USB Own bit (same) */
/* Bits 16-25: Byte Count bits (same) */
/* Offset 4: BUFFER_ADDRESS, 32-bit Buffer Address bits */
/************************************************************************************
* Public Types
************************************************************************************/
#ifndef __ASSEMBLY__
/* Buffer Descriptor Status Register layout. */
struct usbotg_bdtentry_s
{
uint32_t status; /* Status, byte count, and PID */
uint8_t *addr; /* Buffer address */
};
/************************************************************************************
* Inline Functions
************************************************************************************/

View File

@ -48,6 +48,10 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
ifeq ($(CONFIG_PIC32MX_USBDEV),y)
CSRCS += up_usbdev.c
endif
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif

View File

@ -2,7 +2,7 @@
* configs/sure-pic32mx/src/sure-internal.h
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -81,7 +81,7 @@ extern "C" {
* Name: pic32mx_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PCB Logic board.
* Called to configure SPI chip select GPIO pins for the Sure PIC32MX Logic board.
*
************************************************************************************/
@ -89,6 +89,18 @@ extern "C" {
EXTERN void weak_function pic32mx_spiinitialize(void);
#endif
/************************************************************************************
* Name: pic32mx_usdbinitialize
*
* Description:
* Called to configure the mini-B PHY on the Sure PIC32MX board for the USB device
*
************************************************************************************/
#if defined(CONFIG_PIC32MX_USBDEV)
EXTERN void weak_function pic32mx_usdbinitialize(void);
#endif
/************************************************************************************
* Name: pic32mx_ledinit
*

View File

@ -85,6 +85,15 @@ void pic32mx_boardinitialize(void)
}
#endif
/* Configure the mini-B PHY on the Sure PIC32MX board for the USB device */
#if defined(CONFIG_PIC32MX_USBDEV)
if (pic32mx_usbdevinitialize)
{
pic32mx_usbdevinitialize();
}
#endif
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS

View File

@ -1,9 +1,9 @@
/************************************************************************************
* configs/sure-pic32mx/src/up_ssp.c
* arch/arm/src/board/up_ssp.c
* configs/sure-pic32mx/src/up_spi.c
* arch/arm/src/board/up_spi.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -65,16 +65,16 @@
*/
#ifdef CONFIG_SPI_DEBUG
# define sspdbg lldbg
# define spidbg lldbg
# ifdef CONFIG_SPI_VERBOSE
# define sspvdbg lldbg
# define spivdbg lldbg
# else
# define sspvdbg(x...)
# define spivdbg(x...)
# endif
#else
# undef CONFIG_SPI_VERBOSE
# define sspdbg(x...)
# define sspvdbg(x...)
# define spidbg(x...)
# define spivdbg(x...)
#endif
/************************************************************************************
@ -86,14 +86,14 @@
************************************************************************************/
/************************************************************************************
* Name: pic32mx_sspinitialize
* Name: pic32mx_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Sure PIC32MX board.
*
************************************************************************************/
void weak_function pic32mx_sspinitialize(void)
void weak_function pic32mx_spiinitialize(void)
{
/* Configure the SPI2 chip select GPIOs */
@ -130,13 +130,13 @@ void weak_function pic32mx_sspinitialize(void)
#ifdef CONFIG_PIC32MX_SPI2
void pic32mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
uint8_t pic32mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
spidbg("Returning nothing\n");
#warning "Missing logic"
return 0;
}

View File

@ -165,4 +165,10 @@ if [ ! -z "${appdir}" ]; then
echo "CONFIG_APPS_DIR=\"$appdir\"" >> "${TOPDIR}/.configX"
fi
fi
# install the final .configX only if it differs from the existing
# .config file.
install -C "${TOPDIR}/.configX" "${TOPDIR}/.config"
rm -f "${TOPDIR}/.configX"