<option id="gnu.c.compiler.option.preprocessor.undef.symbol.415279897" name="Undefined symbols (-U)" superClass="gnu.c.compiler.option.preprocessor.undef.symbol"/>\r
<option id="gnu.c.compiler.option.include.paths.383148579" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" valueType="includePath">\r
<listOptionValue builtIn="false" value=""${workspace_loc:/RTOSDemo_RDB1768/src/FreeRTOS/include}""/>\r
+<listOptionValue builtIn="false" value=""${workspace_loc:/RTOSDemo_RDB1768/src/LPCUSB}""/>\r
<listOptionValue builtIn="false" value=""${workspace_loc:/RTOSDemo_RDB1768/src/LCD}""/>\r
<listOptionValue builtIn="false" value=""${workspace_loc:/RTOSDemo_RDB1768/src/webserver}""/>\r
<listOptionValue builtIn="false" value=""${workspace_loc:/RTOSDemo_RDB1768/src/Common Demo Tasks/include}""/>\r
<projectStorage><?xml version="1.0" encoding="UTF-8"?> \r
<TargetConfig> \r
<Properties property_0="" property_1="" property_2="" property_3="NXP" property_4="LPC1768" property_count="5" version="1"/> \r
-<infoList vendor="NXP"><info chip="LPC1768" match_id="0x00013f37,0x26013F37" name="LPC1768"><chip><name>LPC1768</name> \r
+<infoList vendor="NXP"><info chip="LPC1768" match_id="0x00013f37,0x26013F37" name="LPC1768" package="lpc17_lqfp100.xml"><chip><name>LPC1768</name> \r
<family>LPC17xx</family> \r
<vendor>NXP (formerly Philips)</vendor> \r
<reset board="None" core="Real" sys="Real"/> \r
<peripheralInstance derived_from="LPC17_I2C" determined="infoFile" enable="SYSCTL.PCONP.PCI2C0&amp;0x1" id="I2C0" location="0x4001C000"/> \r
<peripheralInstance derived_from="LPC17_I2C" determined="infoFile" enable="SYSCTL.PCONP.PCI2C1&amp;0x1" id="I2C1" location="0x4005C000"/> \r
<peripheralInstance derived_from="LPC17_I2C" determined="infoFile" enable="SYSCTL.PCONP.PCI2C2&amp;0x1" id="I2C2" location="0x400A0000"/> \r
-<peripheralInstance derived_from="LPC17_DMA" determined="infoFile" enable="SYSCTL.PCONP.PCDMA&amp;0x1" id="DMA" location="0x50004000"/> \r
+<peripheralInstance derived_from="LPC17_DMA" determined="infoFile" enable="SYSCTL.PCONP.PCGPDMA&amp;0x1" id="DMA" location="0x50004000"/> \r
<peripheralInstance derived_from="LPC17_ENET" determined="infoFile" enable="SYSCTL.PCONP.PCENET&amp;0x1" id="ENET" location="0x50000000"/> \r
<peripheralInstance derived_from="CM3_DCR" determined="infoFile" id="DCR" location="0xE000EDF0"/> \r
<peripheralInstance derived_from="LPC17_PCB" determined="infoFile" id="PCB" location="0x4002c000"/> \r
#define configUSE_IDLE_HOOK 0\r
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )\r
#define configUSE_TICK_HOOK 1\r
-#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 64000000 )\r
+#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 99000000 )\r
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )\r
#define configMINIMAL_STACK_SIZE ( ( unsigned portSHORT ) 80 )\r
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 19 * 1024 ) )\r
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( 5 << (8 - configPRIO_BITS) )\r
\r
/* Priorities passed to NVIC_SetPriority() do not require shifting as the\r
-function does the shifting itself. */\r
+function does the shifting itself. Note these priorities need to be equal to\r
+or lower than configMAX_SYSCALL_INTERRUPT_PRIORITY - therefore the numeric\r
+value needs to be equal to or greater than 5 (on the Cortex M3 the lower the\r
+numeric value the higher the interrupt priority). */\r
#define configEMAC_INTERRUPT_PRIORITY 5\r
+#define configUSB_INTERRUPT_PRIORITY 6\r
\r
\r
\r
--- /dev/null
+/*\r
+ LPCUSB, an USB device driver for LPC microcontrollers \r
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)\r
+\r
+ Redistribution and use in source and binary forms, with or without\r
+ modification, are permitted provided that the following conditions are met:\r
+\r
+ 1. Redistributions of source code must retain the above copyright\r
+ notice, this list of conditions and the following disclaimer.\r
+ 2. Redistributions in binary form must reproduce the above copyright\r
+ notice, this list of conditions and the following disclaimer in the\r
+ documentation and/or other materials provided with the distribution.\r
+ 3. The name of the author may not be used to endorse or promote products\r
+ derived from this software without specific prior written permission.\r
+\r
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR\r
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES\r
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.\r
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, \r
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT\r
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF\r
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+*/\r
+\r
+/*\r
+ Minimal implementation of a USB serial port, using the CDC class.\r
+ This example application simply echoes everything it receives right back\r
+ to the host.\r
+\r
+ Windows:\r
+ Extract the usbser.sys file from .cab file in C:\WINDOWS\Driver Cache\i386\r
+ and store it somewhere (C:\temp is a good place) along with the usbser.inf\r
+ file. Then plug in the LPC176x and direct windows to the usbser driver.\r
+ Windows then creates an extra COMx port that you can open in a terminal\r
+ program, like hyperterminal. [Note for FreeRTOS users - the required .inf\r
+ file is included in the project directory.]\r
+\r
+ Linux:\r
+ The device should be recognised automatically by the cdc_acm driver,\r
+ which creates a /dev/ttyACMx device file that acts just like a regular\r
+ serial port.\r
+\r
+*/\r
+\r
+#include "FreeRTOS.h"\r
+#include "queue.h"\r
+\r
+#include <stdio.h>\r
+#include <string.h>\r
+\r
+#include "usbapi.h"\r
+#include "usbdebug.h"\r
+#include "usbstruct.h"\r
+\r
+#include "LPC17xx.h"\r
+\r
+#define usbMAX_SEND_BLOCK ( 20 / portTICK_RATE_MS )\r
+#define usbBUFFER_LEN ( 20 )\r
+\r
+#define INCREMENT_ECHO_BY 1\r
+#define BAUD_RATE 115200\r
+\r
+#define INT_IN_EP 0x81\r
+#define BULK_OUT_EP 0x05\r
+#define BULK_IN_EP 0x82\r
+\r
+#define MAX_PACKET_SIZE 64\r
+\r
+#define LE_WORD(x) ((x)&0xFF),((x)>>8)\r
+\r
+// CDC definitions\r
+#define CS_INTERFACE 0x24\r
+#define CS_ENDPOINT 0x25\r
+\r
+#define SET_LINE_CODING 0x20\r
+#define GET_LINE_CODING 0x21\r
+#define SET_CONTROL_LINE_STATE 0x22\r
+\r
+// data structure for GET_LINE_CODING / SET_LINE_CODING class requests\r
+typedef struct {\r
+ unsigned long dwDTERate;\r
+ unsigned char bCharFormat;\r
+ unsigned char bParityType;\r
+ unsigned char bDataBits;\r
+} TLineCoding;\r
+\r
+static TLineCoding LineCoding = {115200, 0, 0, 8};\r
+static unsigned char abBulkBuf[64];\r
+static unsigned char abClassReqData[8];\r
+\r
+static xQueueHandle xRxedChars = NULL, xCharsForTx = NULL;\r
+\r
+// forward declaration of interrupt handler\r
+void USBIntHandler(void);\r
+\r
+static const unsigned char abDescriptors[] = {\r
+\r
+// device descriptor\r
+ 0x12,\r
+ DESC_DEVICE,\r
+ LE_WORD(0x0101), // bcdUSB\r
+ 0x02, // bDeviceClass\r
+ 0x00, // bDeviceSubClass\r
+ 0x00, // bDeviceProtocol\r
+ MAX_PACKET_SIZE0, // bMaxPacketSize\r
+ LE_WORD(0xFFFF), // idVendor\r
+ LE_WORD(0x0005), // idProduct\r
+ LE_WORD(0x0100), // bcdDevice\r
+ 0x01, // iManufacturer\r
+ 0x02, // iProduct\r
+ 0x03, // iSerialNumber\r
+ 0x01, // bNumConfigurations\r
+\r
+// configuration descriptor\r
+ 0x09,\r
+ DESC_CONFIGURATION,\r
+ LE_WORD(67), // wTotalLength\r
+ 0x02, // bNumInterfaces\r
+ 0x01, // bConfigurationValue\r
+ 0x00, // iConfiguration\r
+ 0xC0, // bmAttributes\r
+ 0x32, // bMaxPower\r
+// control class interface\r
+ 0x09,\r
+ DESC_INTERFACE,\r
+ 0x00, // bInterfaceNumber\r
+ 0x00, // bAlternateSetting\r
+ 0x01, // bNumEndPoints\r
+ 0x02, // bInterfaceClass\r
+ 0x02, // bInterfaceSubClass\r
+ 0x01, // bInterfaceProtocol, linux requires value of 1 for the cdc_acm module\r
+ 0x00, // iInterface\r
+// header functional descriptor\r
+ 0x05,\r
+ CS_INTERFACE,\r
+ 0x00,\r
+ LE_WORD(0x0110),\r
+// call management functional descriptor\r
+ 0x05,\r
+ CS_INTERFACE,\r
+ 0x01,\r
+ 0x01, // bmCapabilities = device handles call management\r
+ 0x01, // bDataInterface\r
+// ACM functional descriptor\r
+ 0x04,\r
+ CS_INTERFACE,\r
+ 0x02,\r
+ 0x02, // bmCapabilities\r
+// union functional descriptor\r
+ 0x05,\r
+ CS_INTERFACE,\r
+ 0x06,\r
+ 0x00, // bMasterInterface\r
+ 0x01, // bSlaveInterface0\r
+// notification EP\r
+ 0x07,\r
+ DESC_ENDPOINT,\r
+ INT_IN_EP, // bEndpointAddress\r
+ 0x03, // bmAttributes = intr\r
+ LE_WORD(8), // wMaxPacketSize\r
+ 0x0A, // bInterval\r
+// data class interface descriptor\r
+ 0x09,\r
+ DESC_INTERFACE,\r
+ 0x01, // bInterfaceNumber\r
+ 0x00, // bAlternateSetting\r
+ 0x02, // bNumEndPoints\r
+ 0x0A, // bInterfaceClass = data\r
+ 0x00, // bInterfaceSubClass\r
+ 0x00, // bInterfaceProtocol\r
+ 0x00, // iInterface\r
+// data EP OUT\r
+ 0x07,\r
+ DESC_ENDPOINT,\r
+ BULK_OUT_EP, // bEndpointAddress\r
+ 0x02, // bmAttributes = bulk\r
+ LE_WORD(MAX_PACKET_SIZE), // wMaxPacketSize\r
+ 0x00, // bInterval\r
+// data EP in\r
+ 0x07,\r
+ DESC_ENDPOINT,\r
+ BULK_IN_EP, // bEndpointAddress\r
+ 0x02, // bmAttributes = bulk\r
+ LE_WORD(MAX_PACKET_SIZE), // wMaxPacketSize\r
+ 0x00, // bInterval\r
+ \r
+ // string descriptors\r
+ 0x04,\r
+ DESC_STRING,\r
+ LE_WORD(0x0409),\r
+\r
+ 0x0E,\r
+ DESC_STRING,\r
+ 'L', 0, 'P', 0, 'C', 0, 'U', 0, 'S', 0, 'B', 0,\r
+\r
+ 0x14,\r
+ DESC_STRING,\r
+ 'U', 0, 'S', 0, 'B', 0, 'S', 0, 'e', 0, 'r', 0, 'i', 0, 'a', 0, 'l', 0,\r
+\r
+ 0x12,\r
+ DESC_STRING,\r
+ 'D', 0, 'E', 0, 'A', 0, 'D', 0, 'C', 0, '0', 0, 'D', 0, 'E', 0,\r
+\r
+// terminating zero\r
+ 0\r
+};\r
+\r
+\r
+/**\r
+ Local function to handle incoming bulk data\r
+ \r
+ @param [in] bEP\r
+ @param [in] bEPStatus\r
+ */\r
+static void BulkOut(unsigned char bEP, unsigned char bEPStatus)\r
+{\r
+ int i, iLen;\r
+ long lHigherPriorityTaskWoken = pdFALSE;\r
+\r
+ ( void ) bEPStatus;\r
+ \r
+ // get data from USB into intermediate buffer\r
+ iLen = USBHwEPRead(bEP, abBulkBuf, sizeof(abBulkBuf));\r
+ for (i = 0; i < iLen; i++) {\r
+ // put into queue\r
+ xQueueSendFromISR( xRxedChars, &( abBulkBuf[ i ] ), &lHigherPriorityTaskWoken ); \r
+ }\r
+ \r
+ portEND_SWITCHING_ISR( lHigherPriorityTaskWoken );\r
+}\r
+\r
+\r
+/**\r
+ Local function to handle outgoing bulk data\r
+ \r
+ @param [in] bEP\r
+ @param [in] bEPStatus\r
+ */\r
+static void BulkIn(unsigned char bEP, unsigned char bEPStatus)\r
+{\r
+ int i, iLen;\r
+ long lHigherPriorityTaskWoken = pdFALSE;\r
+\r
+ ( void ) bEPStatus;\r
+ \r
+ if (uxQueueMessagesWaitingFromISR( xCharsForTx ) == 0) {\r
+ // no more data, disable further NAK interrupts until next USB frame\r
+ USBHwNakIntEnable(0);\r
+ return;\r
+ }\r
+\r
+ // get bytes from transmit FIFO into intermediate buffer\r
+ for (i = 0; i < MAX_PACKET_SIZE; i++) {\r
+ if( xQueueReceiveFromISR( xCharsForTx, ( &abBulkBuf[i] ), &lHigherPriorityTaskWoken ) != pdPASS )\r
+ {\r
+ break;\r
+ }\r
+ }\r
+ iLen = i;\r
+ \r
+ // send over USB\r
+ if (iLen > 0) {\r
+ USBHwEPWrite(bEP, abBulkBuf, iLen);\r
+ }\r
+ \r
+ portEND_SWITCHING_ISR( lHigherPriorityTaskWoken );\r
+}\r
+\r
+\r
+/**\r
+ Local function to handle the USB-CDC class requests\r
+ \r
+ @param [in] pSetup\r
+ @param [out] piLen\r
+ @param [out] ppbData\r
+ */\r
+static BOOL HandleClassRequest(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)\r
+{\r
+ switch (pSetup->bRequest) {\r
+\r
+ // set line coding\r
+ case SET_LINE_CODING:\r
+DBG("SET_LINE_CODING\n");\r
+ memcpy((unsigned char *)&LineCoding, *ppbData, 7);\r
+ *piLen = 7;\r
+DBG("dwDTERate=%u, bCharFormat=%u, bParityType=%u, bDataBits=%u\n",\r
+ LineCoding.dwDTERate,\r
+ LineCoding.bCharFormat,\r
+ LineCoding.bParityType,\r
+ LineCoding.bDataBits);\r
+ break;\r
+\r
+ // get line coding\r
+ case GET_LINE_CODING:\r
+DBG("GET_LINE_CODING\n");\r
+ *ppbData = (unsigned char *)&LineCoding;\r
+ *piLen = 7;\r
+ break;\r
+\r
+ // set control line state\r
+ case SET_CONTROL_LINE_STATE:\r
+ // bit0 = DTR, bit = RTS\r
+DBG("SET_CONTROL_LINE_STATE %X\n", pSetup->wValue);\r
+ break;\r
+\r
+ default:\r
+ return FALSE;\r
+ }\r
+ return TRUE;\r
+}\r
+\r
+\r
+/**\r
+ Writes one character to VCOM port\r
+ \r
+ @param [in] c character to write\r
+ @returns character written, or EOF if character could not be written\r
+ */\r
+int VCOM_putchar(int c)\r
+{\r
+char cc = ( char ) c;\r
+\r
+ if( xQueueSend( xCharsForTx, &cc, usbMAX_SEND_BLOCK ) == pdPASS )\r
+ {\r
+ return c;\r
+ }\r
+ else\r
+ {\r
+ return EOF;\r
+ }\r
+}\r
+\r
+\r
+/**\r
+ Reads one character from VCOM port\r
+ \r
+ @returns character read, or EOF if character could not be read\r
+ */\r
+int VCOM_getchar(void)\r
+{\r
+ unsigned char c;\r
+ \r
+ /* Block the task until a character is available. */\r
+ xQueueReceive( xRxedChars, &c, portMAX_DELAY );\r
+ return c;\r
+}\r
+\r
+\r
+/**\r
+ Interrupt handler\r
+ \r
+ Simply calls the USB ISR\r
+ */\r
+//void USBIntHandler(void)\r
+void USB_IRQHandler(void)\r
+{\r
+ USBHwISR();\r
+}\r
+\r
+\r
+static void USBFrameHandler(unsigned short wFrame)\r
+{\r
+ ( void ) wFrame;\r
+ \r
+ if( uxQueueMessagesWaitingFromISR( xCharsForTx ) > 0 )\r
+ {\r
+ // data available, enable NAK interrupt on bulk in\r
+ USBHwNakIntEnable(INACK_BI);\r
+ }\r
+}\r
+\r
+// CodeRed - added CPUcpsie\r
+\r
+unsigned long CPUcpsie(void)\r
+{\r
+ unsigned long ulRet;\r
+\r
+ //\r
+ // Read PRIMASK and enable interrupts.\r
+ //\r
+ __asm(" mrs %0, PRIMASK\n"\r
+ " cpsie i\n"\r
+ " bx lr\n"\r
+ : "=r" (ulRet));\r
+\r
+ //\r
+ // The return is handled in the inline assembly, but the compiler will\r
+ // still complain if there is not an explicit return here (despite the fact\r
+ // that this does not result in any code being produced because of the\r
+ // naked attribute).\r
+ //\r
+ return(ulRet);\r
+}\r
+\r
+void vUSBTask( void *pvParameters )\r
+{\r
+ int c;\r
+ \r
+ /* Just to prevent compiler warnings about the unused parameter. */\r
+ ( void ) pvParameters;\r
+ DBG("Initialising USB stack\n");\r
+\r
+ xRxedChars = xQueueCreate( usbBUFFER_LEN, sizeof( char ) );\r
+ xCharsForTx = xQueueCreate( usbBUFFER_LEN, sizeof( char ) );\r
+\r
+ if( ( xRxedChars == NULL ) || ( xCharsForTx == NULL ) )\r
+ {\r
+ /* Not enough heap available to create the buffer queues, can't do\r
+ anything so just delete ourselves. */\r
+ vTaskDelete( NULL );\r
+ }\r
+ \r
+ \r
+ // initialise stack\r
+ USBInit();\r
+\r
+ // register descriptors\r
+ USBRegisterDescriptors(abDescriptors);\r
+\r
+ // register class request handler\r
+ USBRegisterRequestHandler(REQTYPE_TYPE_CLASS, HandleClassRequest, abClassReqData);\r
+\r
+ // register endpoint handlers\r
+ USBHwRegisterEPIntHandler(INT_IN_EP, NULL);\r
+ USBHwRegisterEPIntHandler(BULK_IN_EP, BulkIn);\r
+ USBHwRegisterEPIntHandler(BULK_OUT_EP, BulkOut);\r
+ \r
+ // register frame handler\r
+ USBHwRegisterFrameHandler(USBFrameHandler);\r
+\r
+ // enable bulk-in interrupts on NAKs\r
+ USBHwNakIntEnable(INACK_BI);\r
+\r
+ DBG("Starting USB communication\n");\r
+\r
+ NVIC_SetPriority( USB_IRQn, configUSB_INTERRUPT_PRIORITY );\r
+ NVIC_EnableIRQ( USB_IRQn );\r
+ \r
+ // connect to bus\r
+ \r
+ DBG("Connecting to USB bus\n");\r
+ USBHwConnect(TRUE);\r
+\r
+ // echo any character received (do USB stuff in interrupt)\r
+ for( ;; )\r
+ {\r
+ c = VCOM_getchar();\r
+ if (c != EOF) \r
+ {\r
+ // Echo character back with INCREMENT_ECHO_BY offset, so for example if\r
+ // INCREMENT_ECHO_BY is 1 and 'A' is received, 'B' will be echoed back.\r
+ VCOM_putchar(c + INCREMENT_ECHO_BY );\r
+ }\r
+ }\r
+}\r
+\r
--- /dev/null
+/*****************************************************************************\r
+ * type.h: Type definition Header file for NXP LPC17xx Family \r
+ * Microprocessors\r
+ *\r
+ * Copyright(C) 2008, NXP Semiconductor\r
+ * All rights reserved.\r
+ *\r
+ * History\r
+ * 2008.08.21 ver 1.00 Prelimnary version, first Release\r
+ *\r
+******************************************************************************/\r
+#ifndef __TYPE_H__\r
+#define __TYPE_H__\r
+\r
+#ifndef NULL\r
+#define NULL ((void *)0)\r
+#endif\r
+\r
+#ifndef FALSE\r
+#define FALSE (0)\r
+#endif\r
+\r
+#ifndef TRUE\r
+#define TRUE (1)\r
+#endif\r
+\r
+typedef unsigned char BYTE;\r
+typedef unsigned short WORD;\r
+typedef unsigned long DWORD;\r
+typedef unsigned int BOOL;\r
+\r
+typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;\r
+typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;\r
+\r
+/* Pointer to Function returning Void (any number of parameters) */\r
+typedef void (*PFV)();\r
+\r
+#endif /* __TYPE_H__ */\r
--- /dev/null
+/*\r
+ LPCUSB, an USB device driver for LPC microcontrollers \r
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)\r
+\r
+ Redistribution and use in source and binary forms, with or without\r
+ modification, are permitted provided that the following conditions are met:\r
+\r
+ 1. Redistributions of source code must retain the above copyright\r
+ notice, this list of conditions and the following disclaimer.\r
+ 2. Redistributions in binary form must reproduce the above copyright\r
+ notice, this list of conditions and the following disclaimer in the\r
+ documentation and/or other materials provided with the distribution.\r
+ 3. The name of the author may not be used to endorse or promote products\r
+ derived from this software without specific prior written permission.\r
+\r
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR\r
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES\r
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.\r
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, \r
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT\r
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF\r
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+*/\r
+\r
+/**\r
+ @file\r
+*/\r
+\r
+#include "usbstruct.h" // for TSetupPacket\r
+\r
+/*************************************************************************\r
+ USB configuration\r
+**************************************************************************/\r
+\r
+#define MAX_PACKET_SIZE0 64 /**< maximum packet size for EP 0 */\r
+\r
+/*************************************************************************\r
+ USB hardware interface\r
+**************************************************************************/\r
+\r
+// endpoint status sent through callback\r
+#define EP_STATUS_DATA (1<<0) /**< EP has data */\r
+#define EP_STATUS_STALLED (1<<1) /**< EP is stalled */\r
+#define EP_STATUS_SETUP (1<<2) /**< EP received setup packet */\r
+#define EP_STATUS_ERROR (1<<3) /**< EP data was overwritten by setup packet */\r
+#define EP_STATUS_NACKED (1<<4) /**< EP sent NAK */\r
+\r
+// device status sent through callback\r
+#define DEV_STATUS_CONNECT (1<<0) /**< device just got connected */\r
+#define DEV_STATUS_SUSPEND (1<<2) /**< device entered suspend state */\r
+#define DEV_STATUS_RESET (1<<4) /**< device just got reset */\r
+\r
+// interrupt bits for NACK events in USBHwNakIntEnable\r
+// (these bits conveniently coincide with the LPC176x USB controller bit)\r
+#define INACK_CI (1<<1) /**< interrupt on NACK for control in */\r
+#define INACK_CO (1<<2) /**< interrupt on NACK for control out */\r
+#define INACK_II (1<<3) /**< interrupt on NACK for interrupt in */\r
+#define INACK_IO (1<<4) /**< interrupt on NACK for interrupt out */\r
+#define INACK_BI (1<<5) /**< interrupt on NACK for bulk in */\r
+#define INACK_BO (1<<6) /**< interrupt on NACK for bulk out */\r
+\r
+BOOL USBHwInit (void);\r
+void USBHwISR (void);\r
+\r
+void USBHwNakIntEnable (unsigned char bIntBits);\r
+\r
+void USBHwConnect (BOOL fConnect);\r
+\r
+void USBHwSetAddress (unsigned char bAddr);\r
+void USBHwConfigDevice (BOOL fConfigured);\r
+\r
+// endpoint operations\r
+void USBHwEPConfig (unsigned char bEP, unsigned short wMaxPacketSize);\r
+int USBHwEPRead (unsigned char bEP, unsigned char *pbBuf, int iMaxLen);\r
+int USBHwEPWrite (unsigned char bEP, unsigned char *pbBuf, int iLen);\r
+void USBHwEPStall (unsigned char bEP, BOOL fStall);\r
+unsigned char USBHwEPGetStatus (unsigned char bEP);\r
+\r
+/** Endpoint interrupt handler callback */\r
+typedef void (TFnEPIntHandler) (unsigned char bEP, unsigned char bEPStatus);\r
+void USBHwRegisterEPIntHandler (unsigned char bEP, TFnEPIntHandler *pfnHandler);\r
+\r
+/** Device status handler callback */\r
+typedef void (TFnDevIntHandler) (unsigned char bDevStatus);\r
+void USBHwRegisterDevIntHandler (TFnDevIntHandler *pfnHandler);\r
+\r
+/** Frame event handler callback */\r
+typedef void (TFnFrameHandler)(unsigned short wFrame);\r
+void USBHwRegisterFrameHandler(TFnFrameHandler *pfnHandler);\r
+\r
+\r
+/*************************************************************************\r
+ USB application interface\r
+**************************************************************************/\r
+\r
+// initialise the complete stack, including HW\r
+BOOL USBInit(void);\r
+\r
+/** Request handler callback (standard, vendor, class) */\r
+typedef BOOL (TFnHandleRequest)(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData);\r
+void USBRegisterRequestHandler(int iType, TFnHandleRequest *pfnHandler, unsigned char *pbDataStore);\r
+void USBRegisterCustomReqHandler(TFnHandleRequest *pfnHandler);\r
+\r
+/** Descriptor handler callback */\r
+typedef BOOL (TFnGetDescriptor)(unsigned short wTypeIndex, unsigned short wLangID, int *piLen, unsigned char **ppbData);\r
+\r
+/** Default standard request handler */\r
+BOOL USBHandleStandardRequest(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData);\r
+\r
+/** Default EP0 handler */\r
+void USBHandleControlTransfer(unsigned char bEP, unsigned char bEPStat);\r
+\r
+/** Descriptor handling */\r
+void USBRegisterDescriptors(const unsigned char *pabDescriptors);\r
+BOOL USBGetDescriptor(unsigned short wTypeIndex, unsigned short wLangID, int *piLen, unsigned char **ppbData);\r
--- /dev/null
+/*
+ LPCUSB, an USB device driver for LPC microcontrollers
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ 3. The name of the author may not be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+
+/** @file
+ Control transfer handler.
+
+ This module handles control transfers and is normally installed on the
+ endpoint 0 callback.
+
+ Control transfers can be of the following type:
+ 0 Standard;
+ 1 Class;
+ 2 Vendor;
+ 3 Reserved.
+
+ A callback can be installed for each of these control transfers using
+ USBRegisterRequestHandler.
+ When an OUT request arrives, data is collected in the data store provided
+ with the USBRegisterRequestHandler call. When the transfer is done, the
+ callback is called.
+ When an IN request arrives, the callback is called immediately to either
+ put the control transfer data in the data store, or to get a pointer to
+ control transfer data. The data is then packetised and sent to the host.
+*/
+
+#include "usbdebug.h"
+
+#include "usbstruct.h"
+#include "usbapi.h"
+
+
+
+#define MAX_CONTROL_SIZE 128 /**< maximum total size of control transfer data */
+#define MAX_REQ_HANDLERS 4 /**< standard, class, vendor, reserved */
+
+static TSetupPacket Setup; /**< setup packet */
+
+static unsigned char *pbData; /**< pointer to data buffer */
+static int iResidue; /**< remaining bytes in buffer */
+static int iLen; /**< total length of control transfer */
+
+/** Array of installed request handler callbacks */
+static TFnHandleRequest *apfnReqHandlers[4] = {NULL, NULL, NULL, NULL};
+/** Array of installed request data pointers */
+static unsigned char *apbDataStore[4] = {NULL, NULL, NULL, NULL};
+
+/**
+ Local function to handle a request by calling one of the installed
+ request handlers.
+
+ In case of data going from host to device, the data is at *ppbData.
+ In case of data going from device to host, the handler can either
+ choose to write its data at *ppbData or update the data pointer.
+
+ @param [in] pSetup The setup packet
+ @param [in,out] *piLen Pointer to data length
+ @param [in,out] ppbData Data buffer.
+
+ @return TRUE if the request was handles successfully
+ */
+static BOOL _HandleRequest(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)
+{
+ TFnHandleRequest *pfnHandler;
+ int iType;
+
+ iType = REQTYPE_GET_TYPE(pSetup->bmRequestType);
+ pfnHandler = apfnReqHandlers[iType];
+ if (pfnHandler == NULL) {
+ DBG("No handler for reqtype %d\n", iType);
+ return FALSE;
+ }
+
+ return pfnHandler(pSetup, piLen, ppbData);
+}
+
+
+/**
+ Local function to stall the control endpoint
+
+ @param [in] bEPStat Endpoint status
+ */
+static void StallControlPipe(unsigned char bEPStat)
+{
+ unsigned char *pb;
+ int i;
+
+ USBHwEPStall(0x80, TRUE);
+
+// dump setup packet
+ DBG("STALL on [");
+ pb = (unsigned char *)&Setup;
+ for (i = 0; i < 8; i++) {
+ DBG(" %02x", *pb++);
+ }
+ DBG("] stat=%x\n", bEPStat);
+}
+
+
+/**
+ Sends next chunk of data (possibly 0 bytes) to host
+ */
+static void DataIn(void)
+{
+ int iChunk;
+
+ if( MAX_PACKET_SIZE0 < iResidue )
+ {
+ iChunk = MAX_PACKET_SIZE0;
+ }
+ else
+ {
+ iChunk = iResidue;
+ }
+
+ USBHwEPWrite(0x80, pbData, iChunk);
+ pbData += iChunk;
+ iResidue -= iChunk;
+}
+
+
+/**
+ * Handles IN/OUT transfers on EP0
+ *
+ * @param [in] bEP Endpoint address
+ * @param [in] bEPStat Endpoint status
+ */
+void USBHandleControlTransfer(unsigned char bEP, unsigned char bEPStat)
+{
+ int iChunk, iType;
+
+ if (bEP == 0x00) {
+ // OUT transfer
+ if (bEPStat & EP_STATUS_SETUP) {
+ // setup packet, reset request message state machine
+ USBHwEPRead(0x00, (unsigned char *)&Setup, sizeof(Setup));
+ DBG("S%x", Setup.bRequest);
+
+ // defaults for data pointer and residue
+ iType = REQTYPE_GET_TYPE(Setup.bmRequestType);
+ pbData = apbDataStore[iType];
+ iResidue = Setup.wLength;
+ iLen = Setup.wLength;
+
+ if ((Setup.wLength == 0) ||
+ (REQTYPE_GET_DIR(Setup.bmRequestType) == REQTYPE_DIR_TO_HOST)) {
+ // ask installed handler to process request
+ if (!_HandleRequest(&Setup, &iLen, &pbData)) {
+ DBG("_HandleRequest1 failed\n");
+ StallControlPipe(bEPStat);
+ return;
+ }
+ // send smallest of requested and offered length
+ if( iLen < Setup.wLength )
+ {
+ iResidue = iLen;
+ }
+ else
+ {
+ iResidue = Setup.wLength;
+ }
+
+ // send first part (possibly a zero-length status message)
+ DataIn();
+ }
+ }
+ else {
+ if (iResidue > 0) {
+ // store data
+ iChunk = USBHwEPRead(0x00, pbData, iResidue);
+ if (iChunk < 0) {
+ StallControlPipe(bEPStat);
+ return;
+ }
+ pbData += iChunk;
+ iResidue -= iChunk;
+ if (iResidue == 0) {
+ // received all, send data to handler
+ iType = REQTYPE_GET_TYPE(Setup.bmRequestType);
+ pbData = apbDataStore[iType];
+ if (!_HandleRequest(&Setup, &iLen, &pbData)) {
+ DBG("_HandleRequest2 failed\n");
+ StallControlPipe(bEPStat);
+ return;
+ }
+ // send status to host
+ DataIn();
+ }
+ }
+ else {
+ // absorb zero-length status message
+ iChunk = USBHwEPRead(0x00, NULL, 0);
+ DBG(iChunk > 0 ? "?" : "");
+ }
+ }
+ }
+ else if (bEP == 0x80) {
+ // IN transfer
+ // send more data if available (possibly a 0-length packet)
+ DataIn();
+ }
+ else {
+ ASSERT(FALSE);
+ }
+}
+
+
+/**
+ Registers a callback for handling requests
+
+ @param [in] iType Type of request, e.g. REQTYPE_TYPE_STANDARD
+ @param [in] *pfnHandler Callback function pointer
+ @param [in] *pbDataStore Data storage area for this type of request
+ */
+void USBRegisterRequestHandler(int iType, TFnHandleRequest *pfnHandler, unsigned char *pbDataStore)
+{
+ ASSERT(iType >= 0);
+ ASSERT(iType < 4);
+ apfnReqHandlers[iType] = pfnHandler;
+ apbDataStore[iType] = pbDataStore;
+}
+
--- /dev/null
+/*
+ LPCUSB, an USB device driver for LPC microcontrollers
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ 3. The name of the author may not be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+// CodeRed - comment out this printf, as will use real one from stdio.h
+// to implement output via semihosting
+
+//int printf(const char *format, ...);
+# include <stdio.h>
+
+#ifdef _DEBUG
+#define DBG printf
+#define ASSERT(x) if(!(x)){DBG("\nAssertion '%s' failed in %s:%s#%d!\n",#x,__FILE__,__FUNCTION__,__LINE__);while(1);}
+#else
+#define DBG(x ...)
+#define ASSERT(x)
+#endif
+
--- /dev/null
+/*\r
+ LPCUSB, an USB device driver for LPC microcontrollers \r
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)\r
+\r
+ Redistribution and use in source and binary forms, with or without\r
+ modification, are permitted provided that the following conditions are met:\r
+\r
+ 1. Redistributions of source code must retain the above copyright\r
+ notice, this list of conditions and the following disclaimer.\r
+ 2. Redistributions in binary form must reproduce the above copyright\r
+ notice, this list of conditions and the following disclaimer in the\r
+ documentation and/or other materials provided with the distribution.\r
+ 3. The name of the author may not be used to endorse or promote products\r
+ derived from this software without specific prior written permission.\r
+\r
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR\r
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES\r
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.\r
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, \r
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT\r
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF\r
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+*/\r
+\r
+\r
+/** @file\r
+ USB hardware layer\r
+ */\r
+\r
+\r
+#include "usbdebug.h"\r
+#include "usbhw_lpc.h"\r
+#include "usbapi.h"\r
+// Configure LED pin functions\r
+//\r
+// LED pin functions\r
+//\r
+// Function Pin Port Bits Pin Select Register\r
+// ------------------- --- ----- ---- -------------------\r
+// P2.0 GPIO Port 2.0 xx P2.0 1:0 PINSEL4\r
+// P2.1 GPIO Port 2.1 xx P2.1 3:2 PINSEL4\r
+// P2.2 GPIO Port 2.2 xx P2.2 5:4 PINSEL4\r
+// P2.3 GPIO Port 2.3 xx P2.3 7:6 PINSEL4\r
+// P2.4 GPIO Port 2.4 xx P2.4 9:8 PINSEL4\r
+// P2.5 GPIO Port 2.5 xx P2.5 11:10 PINSEL4\r
+// P2.6 GPIO Port 2.6 xx P2.6 13:12 PINSEL4\r
+// P2.7 GPIO Port 2.7 xx P2.7 15:14 PINSEL4\r
+//\r
+// OFF - LED state 0\r
+// ON - LED state 1\r
+//\r
+// '*' as GPIO\r
+\r
+#define NO_LEDS 8\r
+\r
+#define LED_0 (1 << 0)\r
+#define LED_1 (1 << 1)\r
+#define LED_2 (1 << 2)\r
+#define LED_3 (1 << 3)\r
+#define LED_4 (1 << 4)\r
+#define LED_5 (1 << 5)\r
+#define LED_6 (1 << 6)\r
+#define LED_7 (1 << 7)\r
+\r
+#ifdef DEBUG\r
+// comment out the following line if you don't want to use debug LEDs\r
+//#define DEBUG_LED\r
+#endif\r
+\r
+#ifdef DEBUG_LED\r
+#define DEBUG_LED_ON(x) FIO2SET = (1 << x);\r
+#define DEBUG_LED_OFF(x) FIO2CLR = (1 << x);\r
+#define DEBUG_LED_INIT(x) PINSEL2 &= ~(0x3 << (2*x)); FIO2DIR |= (1 << x); DEBUG_LED_OFF(x);\r
+#else\r
+#define DEBUG_LED_INIT(x) /**< LED initialisation macro */\r
+#define DEBUG_LED_ON(x) /**< turn LED on */\r
+#define DEBUG_LED_OFF(x) /**< turn LED off */\r
+#endif\r
+\r
+/** Installed device interrupt handler */\r
+static TFnDevIntHandler *_pfnDevIntHandler = NULL;\r
+/** Installed endpoint interrupt handlers */\r
+static TFnEPIntHandler *_apfnEPIntHandlers[16];\r
+/** Installed frame interrupt handlers */\r
+static TFnFrameHandler *_pfnFrameHandler = NULL;\r
+\r
+/** convert from endpoint address to endpoint index */\r
+#define EP2IDX(bEP) ((((bEP)&0xF)<<1)|(((bEP)&0x80)>>7))\r
+/** convert from endpoint index to endpoint address */\r
+#define IDX2EP(idx) ((((idx)<<7)&0x80)|(((idx)>>1)&0xF))\r
+\r
+\r
+\r
+/**\r
+ Local function to wait for a device interrupt (and clear it)\r
+ \r
+ @param [in] dwIntr Bitmask of interrupts to wait for \r
+ */\r
+static void Wait4DevInt(unsigned long dwIntr)\r
+{\r
+ // wait for specific interrupt\r
+ while ((USB->USBDevIntSt & dwIntr) != dwIntr);\r
+ // clear the interrupt bits\r
+ USB->USBDevIntClr = dwIntr;\r
+}\r
+\r
+\r
+/**\r
+ Local function to send a command to the USB protocol engine\r
+ \r
+ @param [in] bCmd Command to send\r
+ */\r
+static void USBHwCmd(unsigned char bCmd)\r
+{\r
+ // clear CDFULL/CCEMTY\r
+ USB->USBDevIntClr = CDFULL | CCEMTY;\r
+ // write command code\r
+ USB->USBCmdCode = 0x00000500 | (bCmd << 16);\r
+ Wait4DevInt(CCEMTY);\r
+}\r
+\r
+\r
+/**\r
+ Local function to send a command + data to the USB protocol engine\r
+ \r
+ @param [in] bCmd Command to send\r
+ @param [in] bData Data to send\r
+ */\r
+static void USBHwCmdWrite(unsigned char bCmd, unsigned short bData)\r
+{\r
+ // write command code\r
+ USBHwCmd(bCmd);\r
+\r
+ // write command data\r
+ USB->USBCmdCode = 0x00000100 | (bData << 16);\r
+ Wait4DevInt(CCEMTY);\r
+}\r
+\r
+\r
+/**\r
+ Local function to send a command to the USB protocol engine and read data\r
+ \r
+ @param [in] bCmd Command to send\r
+\r
+ @return the data\r
+ */\r
+static unsigned char USBHwCmdRead(unsigned char bCmd)\r
+{\r
+ // write command code\r
+ USBHwCmd(bCmd);\r
+ \r
+ // get data\r
+ USB->USBCmdCode = 0x00000200 | (bCmd << 16);\r
+ Wait4DevInt(CDFULL);\r
+ return USB->USBCmdData;\r
+}\r
+\r
+\r
+/**\r
+ 'Realizes' an endpoint, meaning that buffer space is reserved for\r
+ it. An endpoint needs to be realised before it can be used.\r
+ \r
+ From experiments, it appears that a USB reset causes USBReEP to\r
+ re-initialise to 3 (= just the control endpoints).\r
+ However, a USB bus reset does not disturb the USBMaxPSize settings.\r
+ \r
+ @param [in] idx Endpoint index\r
+ @param [in] wMaxPSize Maximum packet size for this endpoint\r
+ */\r
+static void USBHwEPRealize(int idx, unsigned short wMaxPSize)\r
+{\r
+ USB->USBReEP |= (1 << idx);\r
+ USB->USBEpInd = idx;\r
+ USB->USBMaxPSize = wMaxPSize;\r
+ Wait4DevInt(EP_RLZED);\r
+}\r
+\r
+\r
+/**\r
+ Enables or disables an endpoint\r
+ \r
+ @param [in] idx Endpoint index\r
+ @param [in] fEnable TRUE to enable, FALSE to disable\r
+ */\r
+static void USBHwEPEnable(int idx, BOOL fEnable)\r
+{\r
+ USBHwCmdWrite(CMD_EP_SET_STATUS | idx, fEnable ? 0 : EP_DA);\r
+}\r
+\r
+\r
+/**\r
+ Configures an endpoint and enables it\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @param [in] wMaxPacketSize Maximum packet size for this EP\r
+ */\r
+void USBHwEPConfig(unsigned char bEP, unsigned short wMaxPacketSize)\r
+{\r
+ int idx;\r
+ \r
+ idx = EP2IDX(bEP);\r
+ \r
+ // realise EP\r
+ USBHwEPRealize(idx, wMaxPacketSize);\r
+\r
+ // enable EP\r
+ USBHwEPEnable(idx, TRUE);\r
+}\r
+\r
+\r
+/**\r
+ Registers an endpoint event callback\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @param [in] pfnHandler Callback function\r
+ */\r
+void USBHwRegisterEPIntHandler(unsigned char bEP, TFnEPIntHandler *pfnHandler)\r
+{\r
+ int idx;\r
+ \r
+ idx = EP2IDX(bEP);\r
+\r
+ ASSERT(idx<32);\r
+\r
+ /* add handler to list of EP handlers */\r
+ _apfnEPIntHandlers[idx / 2] = pfnHandler;\r
+ \r
+ /* enable EP interrupt */\r
+ USB->USBEpIntEn |= (1 << idx);\r
+ USB->USBDevIntEn |= EP_SLOW;\r
+ \r
+ DBG("Registered handler for EP 0x%x\n", bEP);\r
+}\r
+\r
+\r
+/**\r
+ Registers an device status callback\r
+ \r
+ @param [in] pfnHandler Callback function\r
+ */\r
+void USBHwRegisterDevIntHandler(TFnDevIntHandler *pfnHandler)\r
+{\r
+ _pfnDevIntHandler = pfnHandler;\r
+ \r
+ // enable device interrupt\r
+ USB->USBDevIntEn |= DEV_STAT;\r
+\r
+ DBG("Registered handler for device status\n");\r
+}\r
+\r
+\r
+/**\r
+ Registers the frame callback\r
+ \r
+ @param [in] pfnHandler Callback function\r
+ */\r
+void USBHwRegisterFrameHandler(TFnFrameHandler *pfnHandler)\r
+{\r
+ _pfnFrameHandler = pfnHandler;\r
+ \r
+ // enable device interrupt\r
+ USB->USBDevIntEn |= FRAME;\r
+\r
+ DBG("Registered handler for frame\n");\r
+}\r
+\r
+\r
+/**\r
+ Sets the USB address.\r
+ \r
+ @param [in] bAddr Device address to set\r
+ */\r
+void USBHwSetAddress(unsigned char bAddr)\r
+{\r
+ USBHwCmdWrite(CMD_DEV_SET_ADDRESS, DEV_EN | bAddr);\r
+}\r
+\r
+\r
+/**\r
+ Connects or disconnects from the USB bus\r
+ \r
+ @param [in] fConnect If TRUE, connect, otherwise disconnect\r
+ */\r
+void USBHwConnect(BOOL fConnect)\r
+{\r
+ USBHwCmdWrite(CMD_DEV_STATUS, fConnect ? CON : 0);\r
+}\r
+\r
+\r
+/**\r
+ Enables interrupt on NAK condition\r
+ \r
+ For IN endpoints a NAK is generated when the host wants to read data\r
+ from the device, but none is available in the endpoint buffer.\r
+ For OUT endpoints a NAK is generated when the host wants to write data\r
+ to the device, but the endpoint buffer is still full.\r
+ \r
+ The endpoint interrupt handlers can distinguish regular (ACK) interrupts\r
+ from NAK interrupt by checking the bits in their bEPStatus argument.\r
+ \r
+ @param [in] bIntBits Bitmap indicating which NAK interrupts to enable\r
+ */\r
+void USBHwNakIntEnable(unsigned char bIntBits)\r
+{\r
+ USBHwCmdWrite(CMD_DEV_SET_MODE, bIntBits);\r
+}\r
+\r
+\r
+/**\r
+ Gets the status from a specific endpoint.\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @return Endpoint status byte (containing EP_STATUS_xxx bits)\r
+ */\r
+unsigned char USBHwEPGetStatus(unsigned char bEP)\r
+{\r
+ int idx = EP2IDX(bEP);\r
+\r
+ return USBHwCmdRead(CMD_EP_SELECT | idx);\r
+}\r
+\r
+\r
+/**\r
+ Sets the stalled property of an endpoint\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @param [in] fStall TRUE to stall, FALSE to unstall\r
+ */\r
+void USBHwEPStall(unsigned char bEP, BOOL fStall)\r
+{\r
+ int idx = EP2IDX(bEP);\r
+\r
+ USBHwCmdWrite(CMD_EP_SET_STATUS | idx, fStall ? EP_ST : 0);\r
+}\r
+\r
+\r
+/**\r
+ Writes data to an endpoint buffer\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @param [in] pbBuf Endpoint data\r
+ @param [in] iLen Number of bytes to write\r
+ \r
+ @return TRUE if the data was successfully written or <0 in case of error.\r
+*/\r
+int USBHwEPWrite(unsigned char bEP, unsigned char *pbBuf, int iLen)\r
+{\r
+ int idx;\r
+ \r
+ idx = EP2IDX(bEP);\r
+ \r
+ // set write enable for specific endpoint\r
+ USB->USBCtrl = WR_EN | ((bEP & 0xF) << 2);\r
+ \r
+ // set packet length\r
+ USB->USBTxPLen = iLen;\r
+ \r
+ // write data\r
+ while (USB->USBCtrl & WR_EN) {\r
+ USB->USBTxData = (pbBuf[3] << 24) | (pbBuf[2] << 16) | (pbBuf[1] << 8) | pbBuf[0];\r
+ pbBuf += 4;\r
+ }\r
+\r
+ // select endpoint and validate buffer\r
+ USBHwCmd(CMD_EP_SELECT | idx);\r
+ USBHwCmd(CMD_EP_VALIDATE_BUFFER);\r
+ \r
+ return iLen;\r
+}\r
+\r
+\r
+/**\r
+ Reads data from an endpoint buffer\r
+ \r
+ @param [in] bEP Endpoint number\r
+ @param [in] pbBuf Endpoint data\r
+ @param [in] iMaxLen Maximum number of bytes to read\r
+ \r
+ @return the number of bytes available in the EP (possibly more than iMaxLen),\r
+ or <0 in case of error.\r
+ */\r
+int USBHwEPRead(unsigned char bEP, unsigned char *pbBuf, int iMaxLen)\r
+{\r
+ int i, idx;\r
+ unsigned long dwData, dwLen;\r
+ \r
+ idx = EP2IDX(bEP);\r
+ \r
+ // set read enable bit for specific endpoint\r
+ USB->USBCtrl = RD_EN | ((bEP & 0xF) << 2);\r
+ \r
+ // wait for PKT_RDY\r
+ do {\r
+ dwLen = USB->USBRxPLen;\r
+ } while ((dwLen & PKT_RDY) == 0);\r
+ \r
+ // packet valid?\r
+ if ((dwLen & DV) == 0) {\r
+ return -1;\r
+ }\r
+ \r
+ // get length\r
+ dwLen &= PKT_LNGTH_MASK;\r
+ \r
+ // get data\r
+ dwData = 0;\r
+ for (i = 0; i < dwLen; i++) {\r
+ if ((i % 4) == 0) {\r
+ dwData = USB->USBRxData;\r
+ }\r
+ if ((pbBuf != NULL) && (i < iMaxLen)) {\r
+ pbBuf[i] = dwData & 0xFF;\r
+ }\r
+ dwData >>= 8;\r
+ }\r
+\r
+ // make sure RD_EN is clear\r
+ USB->USBCtrl = 0;\r
+\r
+ // select endpoint and clear buffer\r
+ USBHwCmd(CMD_EP_SELECT | idx);\r
+ USBHwCmd(CMD_EP_CLEAR_BUFFER);\r
+ \r
+ return dwLen;\r
+}\r
+\r
+\r
+/**\r
+ Sets the 'configured' state.\r
+ \r
+ All registered endpoints are 'realised' and enabled, and the\r
+ 'configured' bit is set in the device status register.\r
+ \r
+ @param [in] fConfigured If TRUE, configure device, else unconfigure\r
+ */\r
+void USBHwConfigDevice(BOOL fConfigured)\r
+{\r
+ // set configured bit\r
+ USBHwCmdWrite(CMD_DEV_CONFIG, fConfigured ? CONF_DEVICE : 0);\r
+}\r
+\r
+\r
+/**\r
+ USB interrupt handler\r
+ \r
+ @todo Get all 11 bits of frame number instead of just 8\r
+\r
+ Endpoint interrupts are mapped to the slow interrupt\r
+ */\r
+void USBHwISR(void)\r
+{\r
+ unsigned long dwStatus;\r
+ unsigned long dwIntBit;\r
+ unsigned char bEPStat, bDevStat, bStat;\r
+ int i;\r
+ unsigned short wFrame;\r
+\r
+ // LED9 monitors total time in interrupt routine\r
+ DEBUG_LED_ON(6);\r
+\r
+ // handle device interrupts\r
+ dwStatus = USB->USBDevIntSt;\r
+ \r
+ // frame interrupt\r
+ if (dwStatus & FRAME) {\r
+ // clear int\r
+ USB->USBDevIntClr = FRAME;\r
+ // call handler\r
+ if (_pfnFrameHandler != NULL) {\r
+ wFrame = USBHwCmdRead(CMD_DEV_READ_CUR_FRAME_NR);\r
+ _pfnFrameHandler(wFrame);\r
+ }\r
+ }\r
+ \r
+ // device status interrupt\r
+ if (dwStatus & DEV_STAT) {\r
+ /* Clear DEV_STAT interrupt before reading DEV_STAT register.\r
+ This prevents corrupted device status reads, see\r
+ LPC2148 User manual revision 2, 25 july 2006.\r
+ */\r
+ USB->USBDevIntClr = DEV_STAT;\r
+ bDevStat = USBHwCmdRead(CMD_DEV_STATUS);\r
+ if (bDevStat & (CON_CH | SUS_CH | RST)) {\r
+ // convert device status into something HW independent\r
+ bStat = ((bDevStat & CON) ? DEV_STATUS_CONNECT : 0) |\r
+ ((bDevStat & SUS) ? DEV_STATUS_SUSPEND : 0) |\r
+ ((bDevStat & RST) ? DEV_STATUS_RESET : 0);\r
+ // call handler\r
+ if (_pfnDevIntHandler != NULL) {\r
+ DEBUG_LED_ON(5); \r
+ _pfnDevIntHandler(bStat);\r
+ DEBUG_LED_OFF(5); \r
+ }\r
+ }\r
+ }\r
+ \r
+ // endpoint interrupt\r
+ if (dwStatus & EP_SLOW) {\r
+ // clear EP_SLOW\r
+ USB->USBDevIntClr = EP_SLOW;\r
+ // check all endpoints\r
+ for (i = 0; i < 32; i++) {\r
+ dwIntBit = (1 << i);\r
+ if (USB->USBEpIntSt & dwIntBit) {\r
+ // clear int (and retrieve status)\r
+ USB->USBEpIntClr = dwIntBit;\r
+ Wait4DevInt(CDFULL);\r
+ bEPStat = USB->USBCmdData;\r
+ // convert EP pipe stat into something HW independent\r
+ bStat = ((bEPStat & EPSTAT_FE) ? EP_STATUS_DATA : 0) |\r
+ ((bEPStat & EPSTAT_ST) ? EP_STATUS_STALLED : 0) |\r
+ ((bEPStat & EPSTAT_STP) ? EP_STATUS_SETUP : 0) |\r
+ ((bEPStat & EPSTAT_EPN) ? EP_STATUS_NACKED : 0) |\r
+ ((bEPStat & EPSTAT_PO) ? EP_STATUS_ERROR : 0);\r
+ // call handler\r
+ if (_apfnEPIntHandlers[i / 2] != NULL) {\r
+ DEBUG_LED_ON(7); \r
+ _apfnEPIntHandlers[i / 2](IDX2EP(i), bStat);\r
+ DEBUG_LED_OFF(7);\r
+ }\r
+ }\r
+ }\r
+ }\r
+ \r
+ DEBUG_LED_OFF(6); \r
+}\r
+\r
+\r
+\r
+/**\r
+ Initialises the USB hardware\r
+ \r
+ This function assumes that the hardware is connected as shown in\r
+ section 10.1 of the LPC2148 data sheet:\r
+ * P0.31 controls a switch to connect a 1.5k pull-up to D+ if low.\r
+ * P0.23 is connected to USB VCC.\r
+ \r
+ Embedded artists board: make sure to disconnect P0.23 LED as it\r
+ acts as a pull-up and so prevents detection of USB disconnect.\r
+ \r
+ @return TRUE if the hardware was successfully initialised\r
+ */\r
+BOOL USBHwInit(void)\r
+{\r
+ // P2.9 -> USB_CONNECT\r
+ PINCON->PINSEL4 &= ~0x000C0000;\r
+ PINCON->PINSEL4 |= 0x00040000;\r
+\r
+ // P1.18 -> USB_UP_LED\r
+ // P1.30 -> VBUS\r
+ PINCON->PINSEL3 &= ~0x30000030;\r
+ PINCON->PINSEL3 |= 0x20000010;\r
+\r
+ // P0.29 -> USB_D+\r
+ // P0.30 -> USB_D-\r
+ PINCON->PINSEL1 &= ~0x3C000000;\r
+ PINCON->PINSEL1 |= 0x14000000; \r
+\r
+ // enable PUSB\r
+ SC->PCONP |= (1 << 31);\r
+\r
+ USB->OTGClkCtrl = 0x12; /* Dev clock, AHB clock enable */\r
+ while ((USB->OTGClkSt & 0x12) != 0x12);\r
+ \r
+ // disable/clear all interrupts for now\r
+ USB->USBDevIntEn = 0;\r
+ USB->USBDevIntClr = 0xFFFFFFFF;\r
+ USB->USBDevIntPri = 0;\r
+\r
+ USB->USBEpIntEn = 0;\r
+ USB->USBEpIntClr = 0xFFFFFFFF;\r
+ USB->USBEpIntPri = 0;\r
+\r
+ // by default, only ACKs generate interrupts\r
+ USBHwNakIntEnable(0);\r
+\r
+ return TRUE;\r
+}\r
+\r
--- /dev/null
+/*
+ LPCUSB, an USB device driver for LPC microcontrollers
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ 3. The name of the author may not be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+
+/**
+ Hardware definitions for the LPC176x USB controller
+
+ These are private to the usbhw module
+*/
+
+// CodeRed - pull in defines from NXP header file
+//#include "NXP\LPC17xx\LPC17xx.h"
+#include "LPC17xx.h"
+
+
+// CodeRed - these registers have been renamed on LPC176x
+#define USBReEP USBReEp
+#define OTG_CLK_CTRL USBClkCtrl
+#define OTG_CLK_STAT USBClkSt
+
+/* USBIntSt bits */
+#define USB_INT_REQ_LP (1<<0)
+#define USB_INT_REQ_HP (1<<1)
+#define USB_INT_REQ_DMA (1<<2)
+#define USB_need_clock (1<<8)
+#define EN_USB_BITS (1<<31)
+
+/* USBDevInt... bits */
+#define FRAME (1<<0)
+#define EP_FAST (1<<1)
+#define EP_SLOW (1<<2)
+#define DEV_STAT (1<<3)
+#define CCEMTY (1<<4)
+#define CDFULL (1<<5)
+#define RxENDPKT (1<<6)
+#define TxENDPKT (1<<7)
+#define EP_RLZED (1<<8)
+#define ERR_INT (1<<9)
+
+/* USBRxPLen bits */
+#define PKT_LNGTH (1<<0)
+#define PKT_LNGTH_MASK 0x3FF
+#define DV (1<<10)
+#define PKT_RDY (1<<11)
+
+/* USBCtrl bits */
+#define RD_EN (1<<0)
+#define WR_EN (1<<1)
+#define LOG_ENDPOINT (1<<2)
+
+/* protocol engine command codes */
+ /* device commands */
+#define CMD_DEV_SET_ADDRESS 0xD0
+#define CMD_DEV_CONFIG 0xD8
+#define CMD_DEV_SET_MODE 0xF3
+#define CMD_DEV_READ_CUR_FRAME_NR 0xF5
+#define CMD_DEV_READ_TEST_REG 0xFD
+#define CMD_DEV_STATUS 0xFE /* read/write */
+#define CMD_DEV_GET_ERROR_CODE 0xFF
+#define CMD_DEV_READ_ERROR_STATUS 0xFB
+ /* endpoint commands */
+#define CMD_EP_SELECT 0x00
+#define CMD_EP_SELECT_CLEAR 0x40
+#define CMD_EP_SET_STATUS 0x40
+#define CMD_EP_CLEAR_BUFFER 0xF2
+#define CMD_EP_VALIDATE_BUFFER 0xFA
+
+/* set address command */
+#define DEV_ADDR (1<<0)
+#define DEV_EN (1<<7)
+
+/* configure device command */
+#define CONF_DEVICE (1<<0)
+
+/* set mode command */
+#define AP_CLK (1<<0)
+#define INAK_CI (1<<1)
+#define INAK_CO (1<<2)
+#define INAK_II (1<<3)
+#define INAK_IO (1<<4)
+#define INAK_BI (1<<5)
+#define INAK_BO (1<<6)
+
+/* set get device status command */
+#define CON (1<<0)
+#define CON_CH (1<<1)
+#define SUS (1<<2)
+#define SUS_CH (1<<3)
+#define RST (1<<4)
+
+/* get error code command */
+// ...
+
+/* Select Endpoint command read bits */
+#define EPSTAT_FE (1<<0)
+#define EPSTAT_ST (1<<1)
+#define EPSTAT_STP (1<<2)
+#define EPSTAT_PO (1<<3)
+#define EPSTAT_EPN (1<<4)
+#define EPSTAT_B1FULL (1<<5)
+#define EPSTAT_B2FULL (1<<6)
+
+/* CMD_EP_SET_STATUS command */
+#define EP_ST (1<<0)
+#define EP_DA (1<<5)
+#define EP_RF_MO (1<<6)
+#define EP_CND_ST (1<<7)
+
+/* read error status command */
+#define PID_ERR (1<<0)
+#define UEPKT (1<<1)
+#define DCRC (1<<2)
+#define TIMEOUT (1<<3)
+#define EOP (1<<4)
+#define B_OVRN (1<<5)
+#define BTSTF (1<<6)
+#define TGL_ERR (1<<7)
+
+
+
+
+
+
+
+
--- /dev/null
+/*
+ LPCUSB, an USB device driver for LPC microcontrollers
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ 3. The name of the author may not be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+
+/** @file
+ USB stack initialisation
+ */
+
+
+#include "usbdebug.h"
+#include "usbapi.h"
+
+
+/** data storage area for standard requests */
+static unsigned char abStdReqData[8];
+
+
+/**
+ USB reset handler
+
+ @param [in] bDevStatus Device status
+ */
+static void HandleUsbReset(unsigned char bDevStatus)
+{
+ if (bDevStatus & DEV_STATUS_RESET) {
+ DBG("\n!");
+ }
+}
+
+
+/**
+ Initialises the USB hardware and sets up the USB stack by
+ installing default callbacks.
+
+ @return TRUE if initialisation was successful
+ */
+BOOL USBInit(void)
+{
+ // init hardware
+ USBHwInit();
+
+ // register bus reset handler
+ USBHwRegisterDevIntHandler(HandleUsbReset);
+
+ // register control transfer handler on EP0
+ USBHwRegisterEPIntHandler(0x00, USBHandleControlTransfer);
+ USBHwRegisterEPIntHandler(0x80, USBHandleControlTransfer);
+
+ // setup control endpoints
+ USBHwEPConfig(0x00, MAX_PACKET_SIZE0);
+ USBHwEPConfig(0x80, MAX_PACKET_SIZE0);
+
+ // register standard request handler
+ USBRegisterRequestHandler(REQTYPE_TYPE_STANDARD, USBHandleStandardRequest, abStdReqData);
+
+ return TRUE;
+}
+
--- /dev/null
+/*\r
+ LPCUSB, an USB device driver for LPC microcontrollers \r
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)\r
+\r
+ Redistribution and use in source and binary forms, with or without\r
+ modification, are permitted provided that the following conditions are met:\r
+\r
+ 1. Redistributions of source code must retain the above copyright\r
+ notice, this list of conditions and the following disclaimer.\r
+ 2. Redistributions in binary form must reproduce the above copyright\r
+ notice, this list of conditions and the following disclaimer in the\r
+ documentation and/or other materials provided with the distribution.\r
+ 3. The name of the author may not be used to endorse or promote products\r
+ derived from this software without specific prior written permission.\r
+\r
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR\r
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES\r
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.\r
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, \r
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT\r
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF\r
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+*/\r
+\r
+\r
+/** @file\r
+ Standard request handler.\r
+ \r
+ This modules handles the 'chapter 9' processing, specifically the\r
+ standard device requests in table 9-3 from the universal serial bus\r
+ specification revision 2.0\r
+ \r
+ Specific types of devices may specify additional requests (for example\r
+ HID devices add a GET_DESCRIPTOR request for interfaces), but they\r
+ will not be part of this module.\r
+\r
+ @todo some requests have to return a request error if device not configured:\r
+ @todo GET_INTERFACE, GET_STATUS, SET_INTERFACE, SYNCH_FRAME\r
+ @todo this applies to the following if endpoint != 0:\r
+ @todo SET_FEATURE, GET_FEATURE \r
+*/\r
+\r
+#include "usbdebug.h"\r
+#include "usbstruct.h"\r
+#include "usbapi.h"\r
+\r
+#define MAX_DESC_HANDLERS 4 /**< device, interface, endpoint, other */\r
+\r
+\r
+/* general descriptor field offsets */\r
+#define DESC_bLength 0 /**< length offset */\r
+#define DESC_bDescriptorType 1 /**< descriptor type offset */ \r
+\r
+/* config descriptor field offsets */\r
+#define CONF_DESC_wTotalLength 2 /**< total length offset */\r
+#define CONF_DESC_bConfigurationValue 5 /**< configuration value offset */ \r
+#define CONF_DESC_bmAttributes 7 /**< configuration characteristics */\r
+\r
+/* interface descriptor field offsets */\r
+#define INTF_DESC_bAlternateSetting 3 /**< alternate setting offset */\r
+\r
+/* endpoint descriptor field offsets */\r
+#define ENDP_DESC_bEndpointAddress 2 /**< endpoint address offset */\r
+#define ENDP_DESC_wMaxPacketSize 4 /**< maximum packet size offset */\r
+\r
+\r
+/** Currently selected configuration */\r
+static unsigned char bConfiguration = 0;\r
+/** Installed custom request handler */\r
+static TFnHandleRequest *pfnHandleCustomReq = NULL;\r
+/** Pointer to registered descriptors */\r
+static const unsigned char *pabDescrip = NULL;\r
+\r
+\r
+/**\r
+ Registers a pointer to a descriptor block containing all descriptors\r
+ for the device.\r
+\r
+ @param [in] pabDescriptors The descriptor byte array\r
+ */\r
+void USBRegisterDescriptors(const unsigned char *pabDescriptors)\r
+{\r
+ pabDescrip = pabDescriptors;\r
+}\r
+\r
+\r
+/**\r
+ Parses the list of installed USB descriptors and attempts to find\r
+ the specified USB descriptor.\r
+ \r
+ @param [in] wTypeIndex Type and index of the descriptor\r
+ @param [in] wLangID Language ID of the descriptor (currently unused)\r
+ @param [out] *piLen Descriptor length\r
+ @param [out] *ppbData Descriptor data\r
+ \r
+ @return TRUE if the descriptor was found, FALSE otherwise\r
+ */\r
+BOOL USBGetDescriptor(unsigned short wTypeIndex, unsigned short wLangID, int *piLen, unsigned char **ppbData)\r
+{\r
+ unsigned char bType, bIndex;\r
+ unsigned char *pab;\r
+ int iCurIndex;\r
+ \r
+ ASSERT(pabDescrip != NULL);\r
+\r
+ bType = GET_DESC_TYPE(wTypeIndex);\r
+ bIndex = GET_DESC_INDEX(wTypeIndex);\r
+ \r
+ pab = (unsigned char *)pabDescrip;\r
+ iCurIndex = 0;\r
+ \r
+ while (pab[DESC_bLength] != 0) {\r
+ if (pab[DESC_bDescriptorType] == bType) {\r
+ if (iCurIndex == bIndex) {\r
+ // set data pointer\r
+ *ppbData = pab;\r
+ // get length from structure\r
+ if (bType == DESC_CONFIGURATION) {\r
+ // configuration descriptor is an exception, length is at offset 2 and 3\r
+ *piLen = (pab[CONF_DESC_wTotalLength]) |\r
+ (pab[CONF_DESC_wTotalLength + 1] << 8);\r
+ }\r
+ else {\r
+ // normally length is at offset 0\r
+ *piLen = pab[DESC_bLength];\r
+ }\r
+ return TRUE;\r
+ }\r
+ iCurIndex++;\r
+ }\r
+ // skip to next descriptor\r
+ pab += pab[DESC_bLength];\r
+ }\r
+ // nothing found\r
+ DBG("Desc %x not found!\n", wTypeIndex);\r
+ return FALSE;\r
+}\r
+\r
+\r
+/**\r
+ Configures the device according to the specified configuration index and\r
+ alternate setting by parsing the installed USB descriptor list.\r
+ A configuration index of 0 unconfigures the device.\r
+ \r
+ @param [in] bConfigIndex Configuration index\r
+ @param [in] bAltSetting Alternate setting number\r
+ \r
+ @todo function always returns TRUE, add stricter checking?\r
+ \r
+ @return TRUE if successfully configured, FALSE otherwise\r
+ */\r
+static BOOL USBSetConfiguration(unsigned char bConfigIndex, unsigned char bAltSetting)\r
+{\r
+ unsigned char *pab;\r
+ unsigned char bCurConfig, bCurAltSetting;\r
+ unsigned char bEP;\r
+ unsigned short wMaxPktSize;\r
+ \r
+ ASSERT(pabDescrip != NULL);\r
+\r
+ if (bConfigIndex == 0) {\r
+ // unconfigure device\r
+ USBHwConfigDevice(FALSE);\r
+ }\r
+ else {\r
+ // configure endpoints for this configuration/altsetting\r
+ pab = (unsigned char *)pabDescrip;\r
+ bCurConfig = 0xFF;\r
+ bCurAltSetting = 0xFF;\r
+\r
+ while (pab[DESC_bLength] != 0) {\r
+\r
+ switch (pab[DESC_bDescriptorType]) {\r
+\r
+ case DESC_CONFIGURATION:\r
+ // remember current configuration index\r
+ bCurConfig = pab[CONF_DESC_bConfigurationValue];\r
+ break;\r
+\r
+ case DESC_INTERFACE:\r
+ // remember current alternate setting\r
+ bCurAltSetting = pab[INTF_DESC_bAlternateSetting];\r
+ break;\r
+\r
+ case DESC_ENDPOINT:\r
+ if ((bCurConfig == bConfigIndex) &&\r
+ (bCurAltSetting == bAltSetting)) {\r
+ // endpoint found for desired config and alternate setting\r
+ bEP = pab[ENDP_DESC_bEndpointAddress];\r
+ wMaxPktSize = (pab[ENDP_DESC_wMaxPacketSize]) |\r
+ (pab[ENDP_DESC_wMaxPacketSize + 1] << 8);\r
+ // configure endpoint\r
+ USBHwEPConfig(bEP, wMaxPktSize);\r
+ }\r
+ break;\r
+\r
+ default:\r
+ break;\r
+ }\r
+ // skip to next descriptor\r
+ pab += pab[DESC_bLength];\r
+ }\r
+ \r
+ // configure device\r
+ USBHwConfigDevice(TRUE);\r
+ }\r
+\r
+ return TRUE;\r
+}\r
+\r
+\r
+/**\r
+ Local function to handle a standard device request\r
+ \r
+ @param [in] pSetup The setup packet\r
+ @param [in,out] *piLen Pointer to data length\r
+ @param [in,out] ppbData Data buffer.\r
+\r
+ @return TRUE if the request was handled successfully\r
+ */\r
+static BOOL HandleStdDeviceReq(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)\r
+{\r
+ unsigned char *pbData = *ppbData;\r
+\r
+ switch (pSetup->bRequest) {\r
+ \r
+ case REQ_GET_STATUS:\r
+ // bit 0: self-powered\r
+ // bit 1: remote wakeup = not supported\r
+ pbData[0] = 0;\r
+ pbData[1] = 0;\r
+ *piLen = 2;\r
+ break;\r
+ \r
+ case REQ_SET_ADDRESS:\r
+ USBHwSetAddress(pSetup->wValue);\r
+ break;\r
+\r
+ case REQ_GET_DESCRIPTOR:\r
+ DBG("D%x", pSetup->wValue);\r
+ return USBGetDescriptor(pSetup->wValue, pSetup->wIndex, piLen, ppbData);\r
+\r
+ case REQ_GET_CONFIGURATION:\r
+ // indicate if we are configured\r
+ pbData[0] = bConfiguration;\r
+ *piLen = 1;\r
+ break;\r
+\r
+ case REQ_SET_CONFIGURATION:\r
+ if (!USBSetConfiguration(pSetup->wValue & 0xFF, 0)) {\r
+ DBG("USBSetConfiguration failed!\n");\r
+ return FALSE;\r
+ }\r
+ // configuration successful, update current configuration\r
+ bConfiguration = pSetup->wValue & 0xFF; \r
+ break;\r
+\r
+ case REQ_CLEAR_FEATURE:\r
+ case REQ_SET_FEATURE:\r
+ if (pSetup->wValue == FEA_REMOTE_WAKEUP) {\r
+ // put DEVICE_REMOTE_WAKEUP code here\r
+ }\r
+ if (pSetup->wValue == FEA_TEST_MODE) {\r
+ // put TEST_MODE code here\r
+ }\r
+ return FALSE;\r
+\r
+ case REQ_SET_DESCRIPTOR:\r
+ DBG("Device req %d not implemented\n", pSetup->bRequest);\r
+ return FALSE;\r
+\r
+ default:\r
+ DBG("Illegal device req %d\n", pSetup->bRequest);\r
+ return FALSE;\r
+ }\r
+ \r
+ return TRUE;\r
+}\r
+\r
+\r
+/**\r
+ Local function to handle a standard interface request\r
+ \r
+ @param [in] pSetup The setup packet\r
+ @param [in,out] *piLen Pointer to data length\r
+ @param [in] ppbData Data buffer.\r
+\r
+ @return TRUE if the request was handled successfully\r
+ */\r
+static BOOL HandleStdInterfaceReq(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)\r
+{\r
+ unsigned char *pbData = *ppbData;\r
+\r
+ switch (pSetup->bRequest) {\r
+\r
+ case REQ_GET_STATUS:\r
+ // no bits specified\r
+ pbData[0] = 0;\r
+ pbData[1] = 0;\r
+ *piLen = 2;\r
+ break;\r
+\r
+ case REQ_CLEAR_FEATURE:\r
+ case REQ_SET_FEATURE:\r
+ // not defined for interface\r
+ return FALSE;\r
+ \r
+ case REQ_GET_INTERFACE: // TODO use bNumInterfaces\r
+ // there is only one interface, return n-1 (= 0)\r
+ pbData[0] = 0;\r
+ *piLen = 1;\r
+ break;\r
+ \r
+ case REQ_SET_INTERFACE: // TODO use bNumInterfaces\r
+ // there is only one interface (= 0)\r
+ if (pSetup->wValue != 0) {\r
+ return FALSE;\r
+ }\r
+ *piLen = 0;\r
+ break;\r
+\r
+ default:\r
+ DBG("Illegal interface req %d\n", pSetup->bRequest);\r
+ return FALSE;\r
+ }\r
+\r
+ return TRUE;\r
+}\r
+\r
+\r
+/**\r
+ Local function to handle a standard endpoint request\r
+ \r
+ @param [in] pSetup The setup packet\r
+ @param [in,out] *piLen Pointer to data length\r
+ @param [in] ppbData Data buffer.\r
+\r
+ @return TRUE if the request was handled successfully\r
+ */\r
+static BOOL HandleStdEndPointReq(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)\r
+{\r
+ unsigned char *pbData = *ppbData;\r
+\r
+ switch (pSetup->bRequest) {\r
+ case REQ_GET_STATUS:\r
+ // bit 0 = endpointed halted or not\r
+ pbData[0] = (USBHwEPGetStatus(pSetup->wIndex) & EP_STATUS_STALLED) ? 1 : 0;\r
+ pbData[1] = 0;\r
+ *piLen = 2;\r
+ break;\r
+ \r
+ case REQ_CLEAR_FEATURE:\r
+ if (pSetup->wValue == FEA_ENDPOINT_HALT) {\r
+ // clear HALT by unstalling\r
+ USBHwEPStall(pSetup->wIndex, FALSE);\r
+ break;\r
+ }\r
+ // only ENDPOINT_HALT defined for endpoints\r
+ return FALSE;\r
+ \r
+ case REQ_SET_FEATURE:\r
+ if (pSetup->wValue == FEA_ENDPOINT_HALT) {\r
+ // set HALT by stalling\r
+ USBHwEPStall(pSetup->wIndex, TRUE);\r
+ break;\r
+ }\r
+ // only ENDPOINT_HALT defined for endpoints\r
+ return FALSE;\r
+\r
+ case REQ_SYNCH_FRAME:\r
+ DBG("EP req %d not implemented\n", pSetup->bRequest);\r
+ return FALSE;\r
+\r
+ default:\r
+ DBG("Illegal EP req %d\n", pSetup->bRequest);\r
+ return FALSE;\r
+ }\r
+ \r
+ return TRUE;\r
+}\r
+\r
+\r
+/**\r
+ Default handler for standard ('chapter 9') requests\r
+ \r
+ If a custom request handler was installed, this handler is called first.\r
+ \r
+ @param [in] pSetup The setup packet\r
+ @param [in,out] *piLen Pointer to data length\r
+ @param [in] ppbData Data buffer.\r
+\r
+ @return TRUE if the request was handled successfully\r
+ */\r
+BOOL USBHandleStandardRequest(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)\r
+{\r
+ // try the custom request handler first\r
+ if ((pfnHandleCustomReq != NULL) && pfnHandleCustomReq(pSetup, piLen, ppbData)) {\r
+ return TRUE;\r
+ }\r
+ \r
+ switch (REQTYPE_GET_RECIP(pSetup->bmRequestType)) {\r
+ case REQTYPE_RECIP_DEVICE: return HandleStdDeviceReq(pSetup, piLen, ppbData);\r
+ case REQTYPE_RECIP_INTERFACE: return HandleStdInterfaceReq(pSetup, piLen, ppbData);\r
+ case REQTYPE_RECIP_ENDPOINT: return HandleStdEndPointReq(pSetup, piLen, ppbData);\r
+ default: return FALSE;\r
+ }\r
+}\r
+\r
+\r
+/**\r
+ Registers a callback for custom device requests\r
+ \r
+ In USBHandleStandardRequest, the custom request handler gets a first\r
+ chance at handling the request before it is handed over to the 'chapter 9'\r
+ request handler.\r
+ \r
+ This can be used for example in HID devices, where a REQ_GET_DESCRIPTOR\r
+ request is sent to an interface, which is not covered by the 'chapter 9'\r
+ specification.\r
+ \r
+ @param [in] pfnHandler Callback function pointer\r
+ */\r
+void USBRegisterCustomReqHandler(TFnHandleRequest *pfnHandler)\r
+{\r
+ pfnHandleCustomReq = pfnHandler;\r
+}\r
+\r
--- /dev/null
+/*
+ LPCUSB, an USB device driver for LPC microcontrollers
+ Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ 3. The name of the author may not be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+
+/**
+ Definitions of structures of standard USB packets
+*/
+
+#ifndef _USBSTRUCT_H_
+#define _USBSTRUCT_H_
+
+// CodeRed - include the LPCUSB type.h file rather than NXP one directly
+#include "type.h"
+
+/** setup packet definitions */
+typedef struct {
+ unsigned char bmRequestType; /**< characteristics of the specific request */
+ unsigned char bRequest; /**< specific request */
+ unsigned short wValue; /**< request specific parameter */
+ unsigned short wIndex; /**< request specific parameter */
+ unsigned short wLength; /**< length of data transfered in data phase */
+} TSetupPacket;
+
+
+#define REQTYPE_GET_DIR(x) (((x)>>7)&0x01)
+#define REQTYPE_GET_TYPE(x) (((x)>>5)&0x03)
+#define REQTYPE_GET_RECIP(x) ((x)&0x1F)
+
+#define REQTYPE_DIR_TO_DEVICE 0
+#define REQTYPE_DIR_TO_HOST 1
+
+#define REQTYPE_TYPE_STANDARD 0
+#define REQTYPE_TYPE_CLASS 1
+#define REQTYPE_TYPE_VENDOR 2
+#define REQTYPE_TYPE_RESERVED 3
+
+#define REQTYPE_RECIP_DEVICE 0
+#define REQTYPE_RECIP_INTERFACE 1
+#define REQTYPE_RECIP_ENDPOINT 2
+#define REQTYPE_RECIP_OTHER 3
+
+/* standard requests */
+#define REQ_GET_STATUS 0x00
+#define REQ_CLEAR_FEATURE 0x01
+#define REQ_SET_FEATURE 0x03
+#define REQ_SET_ADDRESS 0x05
+#define REQ_GET_DESCRIPTOR 0x06
+#define REQ_SET_DESCRIPTOR 0x07
+#define REQ_GET_CONFIGURATION 0x08
+#define REQ_SET_CONFIGURATION 0x09
+#define REQ_GET_INTERFACE 0x0A
+#define REQ_SET_INTERFACE 0x0B
+#define REQ_SYNCH_FRAME 0x0C
+
+/* class requests HID */
+#define HID_GET_REPORT 0x01
+#define HID_GET_IDLE 0x02
+#define HID_GET_PROTOCOL 0x03
+#define HID_SET_REPORT 0x09
+#define HID_SET_IDLE 0x0A
+#define HID_SET_PROTOCOL 0x0B
+
+/* feature selectors */
+#define FEA_ENDPOINT_HALT 0x00
+#define FEA_REMOTE_WAKEUP 0x01
+#define FEA_TEST_MODE 0x02
+
+/*
+ USB descriptors
+*/
+
+/** USB descriptor header */
+typedef struct {
+ unsigned char bLength; /**< descriptor length */
+ unsigned char bDescriptorType; /**< descriptor type */
+} TUSBDescHeader;
+
+#define DESC_DEVICE 1
+#define DESC_CONFIGURATION 2
+#define DESC_STRING 3
+#define DESC_INTERFACE 4
+#define DESC_ENDPOINT 5
+#define DESC_DEVICE_QUALIFIER 6
+#define DESC_OTHER_SPEED 7
+#define DESC_INTERFACE_POWER 8
+
+#define DESC_HID_HID 0x21
+#define DESC_HID_REPORT 0x22
+#define DESC_HID_PHYSICAL 0x23
+
+#define GET_DESC_TYPE(x) (((x)>>8)&0xFF)
+#define GET_DESC_INDEX(x) ((x)&0xFF)
+
+#endif /* _USBSTRUCT_H_ */
+
*/\r
\r
\r
-#error The batch file Demo\CORTEX_LPC1768_GCC_RedSuite\CreateProjectDirectoryStructure.bat must be executed before the first build. After executing the batch file hit F5 to refrech the Eclipse project, then delete this line.\r
+//#error The batch file Demo\CORTEX_LPC1768_GCC_RedSuite\CreateProjectDirectoryStructure.bat must be executed before the first build. After executing the batch file hit F5 to refrech the Eclipse project, then delete this line.\r
\r
\r
\r
*\r
* "uIP" task - This is the task that handles the uIP stack. All TCP/IP\r
* processing is performed in this task.\r
+ * \r
+ * "USB" task - Enumerates the USB device as a CDC class, then echoes back all\r
+ * received characters with a configurable offset (for example, if the offset\r
+ * is 1 and 'A' is received then 'B' will be sent back). A dumb terminal such\r
+ * as Hyperterminal can be used to talk to the USB task.\r
*/\r
\r
/* Standard includes. */\r
*/\r
extern void vuIP_Task( void *pvParameters );\r
\r
+/*\r
+ * The task that handles the USB stack.\r
+ */\r
+extern void vUSBTask( void *pvParameters );\r
+\r
/*\r
* Simply returns the current status message for display on served WEB pages.\r
*/\r
vStartRecursiveMutexTasks();\r
vStartLEDFlashTasks( mainFLASH_TASK_PRIORITY );\r
\r
+ /* Create the USB task. */\r
+ xTaskCreate( vUSBTask, ( signed char * ) "USB", configMINIMAL_STACK_SIZE, ( void * ) NULL, tskIDLE_PRIORITY, NULL );\r
+ \r
/* Display the IP address, then create the uIP task. The WEB server runs \r
in this task. */\r
LCDdriver_initialisation();\r
/* Disable TPIU. */\r
PINCON->PINSEL10 = 0;\r
\r
- /* Disconnect the main PLL. */\r
- SC->PLL0CON &= ~PLLCON_PLLC;\r
- SC->PLL0FEED = PLLFEED_FEED1;\r
- SC->PLL0FEED = PLLFEED_FEED2;\r
- while ((SC->PLL0STAT & PLLSTAT_PLLC) != 0);\r
-\r
- /* Turn off the main PLL. */\r
- SC->PLL0CON &= ~PLLCON_PLLE;\r
+ if ( SC->PLL0STAT & ( 1 << 25 ) )\r
+ {\r
+ /* Enable PLL, disconnected. */\r
+ SC->PLL0CON = 1; \r
+ SC->PLL0FEED = PLLFEED_FEED1;\r
+ SC->PLL0FEED = PLLFEED_FEED2;\r
+ }\r
+ \r
+ /* Disable PLL, disconnected. */\r
+ SC->PLL0CON = 0; \r
SC->PLL0FEED = PLLFEED_FEED1;\r
SC->PLL0FEED = PLLFEED_FEED2;\r
- while ((SC->PLL0STAT & PLLSTAT_PLLE) != 0);\r
-\r
- /* No CPU clock divider. */\r
- SC->CCLKCFG = 0;\r
-\r
- /* OSCEN. */\r
- SC->SCS = 0x20;\r
- while ((SC->SCS & 0x40) == 0);\r
-\r
- /* Use main oscillator. */\r
- SC->CLKSRCSEL = 1;\r
- SC->PLL0CFG = (PLLCFG_MUL16 | PLLCFG_DIV1);\r
-\r
+ \r
+ /* Enable main OSC. */\r
+ SC->SCS |= 0x20; \r
+ while( !( SC->SCS & 0x40 ) );\r
+ \r
+ /* select main OSC, 12MHz, as the PLL clock source. */\r
+ SC->CLKSRCSEL = 0x1; \r
+ \r
+ SC->PLL0CFG = 0x0b;\r
SC->PLL0FEED = PLLFEED_FEED1;\r
SC->PLL0FEED = PLLFEED_FEED2;\r
-\r
- /* Activate the PLL by turning it on then feeding the correct\r
- sequence of bytes. */\r
- SC->PLL0CON = PLLCON_PLLE;\r
+ \r
+ /* Enable PLL, disconnected. */\r
+ SC->PLL0CON = 1; \r
SC->PLL0FEED = PLLFEED_FEED1;\r
SC->PLL0FEED = PLLFEED_FEED2;\r
-\r
- /* 6x CPU clock divider (64 MHz) */\r
- SC->CCLKCFG = 5;\r
-\r
- /* Wait for the PLL to lock. */\r
- while ((SC->PLL0STAT & PLLSTAT_PLOCK) == 0);\r
-\r
- /* Connect the PLL. */\r
- SC->PLL0CON = PLLCON_PLLC | PLLCON_PLLE;\r
+ \r
+ /* Set clock divider. */\r
+ SC->CCLKCFG = 0x03;\r
+ \r
+ /* Configure flash accelerator. */\r
+ SC->FLASHCFG = 0x303a;\r
+ \r
+ /* Check lock bit status. */\r
+ while( ( ( SC->PLL0STAT & ( 1 << 26 ) ) == 0 ) ); \r
+ \r
+ /* Enable and connect. */\r
+ SC->PLL0CON = 3; \r
SC->PLL0FEED = PLLFEED_FEED1;\r
SC->PLL0FEED = PLLFEED_FEED2;\r
+ while( ( ( SC->PLL0STAT & ( 1 << 25 ) ) == 0 ) ); \r
+\r
+ \r
+ \r
+ \r
+ /* Configure the clock for the USB. */\r
+ \r
+ if( SC->PLL1STAT & ( 1 << 9 ) )\r
+ {\r
+ /* Enable PLL, disconnected. */\r
+ SC->PLL1CON = 1; \r
+ SC->PLL1FEED = PLLFEED_FEED1;\r
+ SC->PLL1FEED = PLLFEED_FEED2;\r
+ }\r
+ \r
+ /* Disable PLL, disconnected. */\r
+ SC->PLL1CON = 0; \r
+ SC->PLL1FEED = PLLFEED_FEED1;\r
+ SC->PLL1FEED = PLLFEED_FEED2;\r
+ \r
+ SC->PLL1CFG = 0x23;\r
+ SC->PLL1FEED = PLLFEED_FEED1;\r
+ SC->PLL1FEED = PLLFEED_FEED2;\r
+ \r
+ /* Enable PLL, disconnected. */\r
+ SC->PLL1CON = 1; \r
+ SC->PLL1FEED = PLLFEED_FEED1;\r
+ SC->PLL1FEED = PLLFEED_FEED2;\r
+ while( ( ( SC->PLL1STAT & ( 1 << 10 ) ) == 0 ) );\r
+ \r
+ /* Enable and connect. */\r
+ SC->PLL1CON = 3; \r
+ SC->PLL1FEED = PLLFEED_FEED1;\r
+ SC->PLL1FEED = PLLFEED_FEED2;\r
+ while( ( ( SC->PLL1STAT & ( 1 << 9 ) ) == 0 ) );\r
\r
/* Setup the peripheral bus to be the same as the PLL output (64 MHz). */\r
SC->PCLKSEL0 = 0x05555555;\r
{\r
FLASH (rx) : ORIGIN = 0x0 LENGTH = 0x80000\r
SRAM (rwx) : ORIGIN = 0x10000000, LENGTH = 0x8000\r
- AHBSRAM0 : ORIGIN = 0x2007c000, LENGTH = 0x4000\r
- AHBSRAM1 : ORIGIN = 0x20080000, LENGTH = 0x4000\r
+ AHBRAM0 : ORIGIN = 0x2007c000, LENGTH = 0x4000\r
+ AHBRAM1 : ORIGIN = 0x20080000, LENGTH = 0x4000\r
}\r
\r
_vRamTop = 0x10000000 + 0x8000;\r
--- /dev/null
+[Version]\r
+Signature="$Windows NT$"\r
+Class=Ports\r
+ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}\r
+Provider=%LINUX%\r
+DriverVer=08/17/2004,0.0.2.0\r
+; Copyright (C) 2004 Al Borchers (alborchers@steinerpoint.com)\r
+; released under GNU General Public License\r
+\r
+[Manufacturer]\r
+%LINUX%=GSerialDeviceList\r
+\r
+[GSerialDeviceList]\r
+%GSERIAL%=GSerialInstall, USB\VID_FFFF&PID_0005\r
+\r
+[DestinationDirs]\r
+DefaultDestDir=10,System32\Drivers\r
+\r
+[GSerialInstall]\r
+CopyFiles=GSerialCopyFiles\r
+AddReg=GSerialAddReg\r
+\r
+[GSerialCopyFiles]\r
+usbser.sys\r
+\r
+[GSerialAddReg]\r
+HKR,,DevLoader,,*ntkern\r
+HKR,,NTMPDriver,,usbser.sys\r
+HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"\r
+\r
+[GSerialInstall.Services]\r
+AddService = usbser,0x0002,GSerialService\r
+\r
+[GSerialService]\r
+DisplayName = %GSERIAL_DISPLAY_NAME%\r
+ServiceType = 1 ; SERVICE_KERNEL_DRIVER\r
+StartType = 3 ; SERVICE_DEMAND_START\r
+ErrorControl = 1 ; SERVICE_ERROR_NORMAL\r
+ServiceBinary = %10%\System32\Drivers\usbser.sys\r
+LoadOrderGroup = Base\r
+\r
+[Strings]\r
+LINUX = "Linux"\r
+GSERIAL = "USB CDC serial port emulation"\r
+GSERIAL_DISPLAY_NAME = "USB CDC serial port emulation"
\ No newline at end of file