diff --git a/demos/device/keyboard/.cproject b/demos/device/keyboard/.cproject
index d70252934..078e72167 100644
--- a/demos/device/keyboard/.cproject
+++ b/demos/device/keyboard/.cproject
@@ -35,6 +35,7 @@
@@ -59,10 +60,12 @@
diff --git a/demos/device/keyboard/.project b/demos/device/keyboard/.project
index 9b163e2fb..200a329db 100644
--- a/demos/device/keyboard/.project
+++ b/demos/device/keyboard/.project
@@ -4,6 +4,7 @@
CMSISv2p10_LPC13Uxx
+ LPC13Uxx_DriverLib
tinyusb
diff --git a/demos/device/keyboard/descriptors.c b/demos/device/keyboard/descriptors.c
index ceb463afe..06610421d 100644
--- a/demos/device/keyboard/descriptors.c
+++ b/demos/device/keyboard/descriptors.c
@@ -37,8 +37,8 @@
#include "descriptors.h"
-#ifdef CFG_USB_HID_KEYBOARD
-ALIGNED(4) const uint8_t HID_KeyboardReportDescriptor[] = {
+#ifdef CFG_CLASS_HID_KEYBOARD
+ATTR_ALIGNED(4) const uint8_t HID_KeyboardReportDescriptor[] = {
HID_UsagePage ( HID_USAGE_PAGE_GENERIC ),
HID_Usage ( HID_USAGE_GENERIC_KEYBOARD ),
HID_Collection ( HID_Application ),
@@ -81,7 +81,7 @@ ALIGNED(4) const uint8_t HID_KeyboardReportDescriptor[] = {
#endif
#ifdef CFG_USB_HID_MOUSE
-ALIGNED(4) const uint8_t HID_MouseReportDescriptor[] = {
+ATTR_ALIGNED(4) const uint8_t HID_MouseReportDescriptor[] = {
HID_UsagePage ( HID_USAGE_PAGE_GENERIC ),
HID_Usage ( HID_USAGE_GENERIC_MOUSE ),
HID_Collection ( HID_Application ),
@@ -119,7 +119,7 @@ ALIGNED(4) const uint8_t HID_MouseReportDescriptor[] = {
#endif
/* USB Standard Device Descriptor */
-ALIGNED(4) const USB_DEVICE_DESCRIPTOR USB_DeviceDescriptor =
+ATTR_ALIGNED(4) const USB_DEVICE_DESCRIPTOR USB_DeviceDescriptor =
{
.bLength = sizeof(USB_DEVICE_DESCRIPTOR),
.bDescriptorType = USB_DEVICE_DESCRIPTOR_TYPE,
@@ -153,7 +153,7 @@ ALIGNED(4) const USB_DEVICE_DESCRIPTOR USB_DeviceDescriptor =
.bNumConfigurations = 0x01
};
-ALIGNED(4) const USB_FS_CONFIGURATION_DESCRIPTOR USB_FsConfigDescriptor =
+ATTR_ALIGNED(4) const USB_FS_CONFIGURATION_DESCRIPTOR USB_FsConfigDescriptor =
{
.Config =
{
@@ -276,7 +276,7 @@ ALIGNED(4) const USB_FS_CONFIGURATION_DESCRIPTOR USB_FsConfigDescriptor =
},
#endif
- #ifdef CFG_USB_HID_KEYBOARD
+ #ifdef CFG_CLASS_HID_KEYBOARD
///// USB HID Keyboard interface
.HID_KeyboardInterface =
{
@@ -358,7 +358,7 @@ ALIGNED(4) const USB_FS_CONFIGURATION_DESCRIPTOR USB_FsConfigDescriptor =
.ConfigDescTermination = 0,
};
-ALIGNED(4) const USB_STR_DESCRIPTOR USB_StringDescriptor =
+ATTR_ALIGNED(4) const USB_STR_DESCRIPTOR USB_StringDescriptor =
{
.LangID = { .bLength = 0x04, .bDescriptorType = USB_STRING_DESCRIPTOR_TYPE },
.strLangID= {0x0409}, // US English
diff --git a/demos/device/keyboard/descriptors.h b/demos/device/keyboard/descriptors.h
index d73f34dcd..83504e31f 100644
--- a/demos/device/keyboard/descriptors.h
+++ b/demos/device/keyboard/descriptors.h
@@ -88,7 +88,7 @@ typedef PRE_PACK struct POST_PACK _USB_INTERFACE_ASSOCIATION_DESCRIPTOR
///////////////////////////////////////////////////////////////////////
// Interface Assosication Descriptor if device is CDC + other class
-#define IAD_DESC_REQUIRED ( defined(CFG_USB_CDC) && (defined(CFG_USB_HID_KEYBOARD) || defined(CFG_USB_HID_MOUSE)) )
+#define IAD_DESC_REQUIRED ( defined(CFG_USB_CDC) && (CLASS_HID) )
#ifdef CFG_USB_CDC
#define INTERFACES_OF_CDC 2
@@ -96,7 +96,7 @@ typedef PRE_PACK struct POST_PACK _USB_INTERFACE_ASSOCIATION_DESCRIPTOR
#define INTERFACES_OF_CDC 0
#endif
-#ifdef CFG_USB_HID_KEYBOARD
+#ifdef CFG_CLASS_HID_KEYBOARD
#define INTERFACES_OF_HID_KEYBOARD 1
#else
#define INTERFACES_OF_HID_KEYBOARD 0
@@ -157,7 +157,7 @@ typedef struct
USB_ENDPOINT_DESCRIPTOR CDC_DataInEndpoint;
#endif
-#ifdef CFG_USB_HID_KEYBOARD
+#ifdef CFG_CLASS_HID_KEYBOARD
//Keyboard HID Interface
USB_INTERFACE_DESCRIPTOR HID_KeyboardInterface;
HID_DESCRIPTOR HID_KeyboardHID;
diff --git a/demos/device/keyboard/main.c b/demos/device/keyboard/main.c
index 3011c82c8..042117e10 100644
--- a/demos/device/keyboard/main.c
+++ b/demos/device/keyboard/main.c
@@ -13,12 +13,47 @@ __CRP const unsigned int CRP_WORD = CRP_NO_CRP ;
int main(void)
{
+ uint32_t currentSecond, lastSecond;
+ currentSecond = lastSecond = 0;
+
SystemInit();
+
+ systickInit(1);
+ GPIOInit();
+
+ #define CFG_LED_PORT (0)
+ #define CFG_LED_PIN (7)
+ #define CFG_LED_ON (1)
+ #define CFG_LED_OFF (0)
+
+ GPIOSetDir(CFG_LED_PORT, CFG_LED_PIN, 1);
+ LPC_GPIO->CLR[CFG_LED_PORT] = (1 << CFG_LED_PIN);
+
tusb_init();
while (1)
{
+ currentSecond = systickGetSecondsActive();
+ if (currentSecond != lastSecond)
+ {
+ /* Toggle LED once per second */
+ lastSecond = currentSecond;
+ GPIOSetBitValue(CFG_LED_PORT, CFG_LED_PIN, lastSecond % 2);
+ #if !defined(CFG_USB_CDC)
+ if (usb_isConfigured())
+ {
+ #ifdef CFG_CLASS_HID_KEYBOARD
+ uint8_t keys[6] = {HID_USAGE_KEYBOARD_aA};
+ usb_hid_keyboard_sendKeys(0x00, keys, 1);
+ #endif
+
+ #ifdef CFG_USB_HID_MOUSE
+ usb_hid_mouse_send(0, 10, 10);
+ #endif
+ }
+ #endif
+ }
}
return 0;
diff --git a/tinyusb/class/hid.c b/tinyusb/class/hid.c
new file mode 100644
index 000000000..21871d284
--- /dev/null
+++ b/tinyusb/class/hid.c
@@ -0,0 +1,337 @@
+/*
+ * hid.c
+ *
+ * Created on: Nov 27, 2012
+ * Author: hathach (thachha@live.com)
+ */
+
+/*
+ * Software License Agreement (BSD License)
+ * Copyright (c) 2012, hathach (thachha@live.com)
+ * All rights reserved.
+ *
+ * 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.
+ *
+ * This file is part of the tiny usb stack.
+ */
+
+#include "hid.h"
+//#include "../systick/systick.h"
+
+#ifdef CLASS_HID
+
+#ifdef CFG_CLASS_HID_KEYBOARD
+USB_HID_KeyboardReport_t hid_keyboard_report;
+volatile static bool bKeyChanged = false;
+#endif
+
+#ifdef CFG_USB_HID_MOUSE
+USB_HID_MouseReport_t hid_mouse_report;
+volatile static bool bMouseChanged = false;
+#endif
+
+/**************************************************************************/
+/*!
+ @brief Handler for HID_GetReport in the USB ROM driver
+*/
+/**************************************************************************/
+ErrorCode_t HID_GetReport( USBD_HANDLE_T hHid, USB_SETUP_PACKET* pSetup, uint8_t** pBuffer, uint16_t* plength)
+{
+ USB_HID_CTRL_T* pHidCtrl = (USB_HID_CTRL_T*) hHid;
+
+ /* ReportID = SetupPacket.wValue.WB.L; */
+ if (pSetup->wValue.WB.H == HID_REPORT_INPUT)
+ return (ERR_USBD_STALL); /* Not Supported */
+
+ switch (pHidCtrl->protocol)
+ {
+ #ifdef CFG_CLASS_HID_KEYBOARD
+ case HID_PROTOCOL_KEYBOARD:
+ *pBuffer = (uint8_t*) &hid_keyboard_report;
+ *plength = sizeof(USB_HID_KeyboardReport_t);
+
+ if (!bKeyChanged)
+ {
+ memset(pBuffer, 0, *plength);
+ }
+ bKeyChanged = false;
+ break;
+ #endif
+
+ #ifdef CFG_USB_HID_MOUSE
+ case HID_PROTOCOL_MOUSE:
+ *pBuffer = (uint8_t*) &hid_mouse_report;
+ *plength = sizeof(USB_HID_MouseReport_t);
+
+ if (!bMouseChanged)
+ {
+ memset(pBuffer, 0, *plength);
+ }
+ bMouseChanged = false;
+ break;
+ #endif
+
+ default:
+ break;
+ }
+
+ return (LPC_OK);
+}
+
+/**************************************************************************/
+/*!
+ @brief Handler for HIS_SetReport in the USB ROM driver
+*/
+/**************************************************************************/
+ErrorCode_t HID_SetReport( USBD_HANDLE_T hHid, USB_SETUP_PACKET* pSetup, uint8_t** pBuffer, uint16_t length)
+{
+ /* we will reuse standard EP0Buf */
+ if (length == 0)
+ return LPC_OK;
+
+ /* ReportID = SetupPacket.wValue.WB.L; */
+ if (pSetup->wValue.WB.H != HID_REPORT_OUTPUT)
+ return (ERR_USBD_STALL); /* Not Supported */
+
+ return (LPC_OK);
+}
+
+/**************************************************************************/
+/*!
+ @brief HID endpoint in handler for the USB ROM driver
+*/
+/**************************************************************************/
+ErrorCode_t HID_EpIn_Hdlr (USBD_HANDLE_T hUsb, void* data, uint32_t event)
+{
+ if (USB_EVT_IN == event)
+ {
+ USB_HID_CTRL_T* pHidCtrl = (USB_HID_CTRL_T*)data;
+ switch(pHidCtrl->protocol)
+ {
+ #ifdef CFG_CLASS_HID_KEYBOARD
+ case HID_PROTOCOL_KEYBOARD:
+ if (!bKeyChanged)
+ {
+ memset(&hid_keyboard_report, 0, sizeof(USB_HID_KeyboardReport_t));
+ }
+ USBD_API->hw->WriteEP(hUsb, pHidCtrl->epin_adr, (uint8_t*) &hid_keyboard_report, sizeof(USB_HID_KeyboardReport_t));
+ bKeyChanged = false;
+ break;
+ #endif
+
+ #ifdef CFG_USB_HID_MOUSE
+ case HID_PROTOCOL_MOUSE:
+ if (!bMouseChanged)
+ {
+ memset(&hid_mouse_report, 0, sizeof(USB_HID_MouseReport_t));
+ }
+ USBD_API->hw->WriteEP(hUsb, pHidCtrl->epin_adr, (uint8_t*) &hid_mouse_report, sizeof(USB_HID_MouseReport_t));
+ bMouseChanged = false;
+ break;
+ #endif
+
+ default:
+ break;
+ }
+ }
+
+ return LPC_OK;
+}
+
+/**************************************************************************/
+/*!
+ @brief HID endpoint out handler for the USB ROM driver
+*/
+/**************************************************************************/
+ErrorCode_t HID_EpOut_Hdlr (USBD_HANDLE_T hUsb, void* data, uint32_t event)
+{
+ if (USB_EVT_OUT == event)
+ {
+ // not used yet
+ // uint8_t outreport[8];
+ // USB_HID_CTRL_T* pHidCtrl = (USB_HID_CTRL_T*)data;
+ // USBD_API->hw->ReadEP(hUsb, pHidCtrl->epout_adr, outreport);
+ }
+ return LPC_OK;
+}
+
+/**************************************************************************/
+/*!
+ @brief Initialises USB HID using the ROM based drivers
+*/
+/**************************************************************************/
+ErrorCode_t usb_hid_init(USBD_HANDLE_T hUsb, USB_INTERFACE_DESCRIPTOR const *const pIntfDesc, uint8_t const * const pHIDReportDesc, uint32_t ReportDescLength, uint32_t* mem_base, uint32_t* mem_size)
+{
+ USB_HID_REPORT_T reports_data =
+ {
+ .desc = (uint8_t*) pHIDReportDesc,
+ .len = ReportDescLength,
+ .idle_time = 0,
+ };
+
+ USBD_HID_INIT_PARAM_T hid_param =
+ {
+ .mem_base = *mem_base,
+ .mem_size = *mem_size,
+
+ .intf_desc = (uint8_t*)pIntfDesc,
+ .report_data = &reports_data,
+ .max_reports = 1,
+
+ /* user defined functions */
+ .HID_GetReport = HID_GetReport,
+ .HID_SetReport = HID_SetReport,
+ .HID_EpIn_Hdlr = HID_EpIn_Hdlr,
+ .HID_EpOut_Hdlr = HID_EpOut_Hdlr
+ };
+
+ ASSERT( (pIntfDesc != NULL) && (pIntfDesc->bInterfaceClass == USB_DEVICE_CLASS_HUMAN_INTERFACE), ERR_FAILED);
+
+ ASSERT_STATUS( USBD_API->hid->init(hUsb, &hid_param) );
+
+ /* update memory variables */
+ *mem_base = hid_param.mem_base;
+ *mem_size = hid_param.mem_size;
+
+ return LPC_OK;
+}
+
+/**************************************************************************/
+/*!
+
+*/
+/**************************************************************************/
+ErrorCode_t usb_hid_configured(USBD_HANDLE_T hUsb)
+{
+ #ifdef CFG_CLASS_HID_KEYBOARD
+ USBD_API->hw->WriteEP(hUsb , HID_KEYBOARD_EP_IN , (uint8_t* ) &hid_keyboard_report , sizeof(USB_HID_KeyboardReport_t) ); // initial packet for IN endpoint , will not work if omitted
+ #endif
+
+ #ifdef CFG_USB_HID_MOUSE
+ USBD_API->hw->WriteEP(hUsb , HID_MOUSE_EP_IN , (uint8_t* ) &hid_mouse_report , sizeof(USB_HID_MouseReport_t) ); // initial packet for IN endpoint, will not work if omitted
+ #endif
+
+ return LPC_OK;
+}
+
+#ifdef CFG_CLASS_HID_KEYBOARD
+/**************************************************************************/
+/*!
+ @brief Send the supplied key codes out via HID USB keyboard emulation
+
+ @param[in] modifier
+ KB modifier code bits (see USB_HID_KB_KEYMODIFIER_CODE)
+ @param[in] keycodes
+ A buffer containing up to six keycodes
+ @param[in] numkey
+ The number of keys to send (max 6)
+
+ @note Note that for HID KBs, letter codes are not case sensitive. To
+ create an upper-case letter, you need to include the correct
+ KB modifier code(s), for ex: (1 << HID_KEYMODIFIER_LEFTSHIFT)
+
+ @section EXAMPLE
+
+ @code
+
+ // Send an unmodified 'a' character
+ if (usb_isConfigured())
+ {
+ uint8_t keys[6] = {HID_USAGE_KEYBOARD_aA};
+ usb_hid_keyboard_sendKeys(0x00, keys, 1);
+ }
+
+ // Send Windows + 'e' (shortcut for 'explorer.exe')
+ if (usb_isConfigured())
+ {
+ uint8_t keys[6] = {HID_USAGE_KEYBOARD_aA + 'e' - 'a'};
+ usb_hid_keyboard_sendKeys((1<irq > 0)
+ NVIC_DisableIRQ(f->irq);
+}
+
+/**************************************************************************/
+/*!
+ @brief Re-enables the IRQ specified in the FIFO's 'irq' field
+
+ @param[in] f
+ Pointer to the FIFO that should be protected
+*/
+/**************************************************************************/
+static inline void mutex_unlock (fifo_t* f)
+{
+ if (f->irq > 0)
+ NVIC_EnableIRQ(f->irq);
+}
+
+/**************************************************************************/
+/*!
+ @brief Initialises the FIFO buffer
+
+ @param[in] f
+ Pointer to the fifo_t object to intiialize
+ @param[in] buffer
+ Pointer to the buffer's location in memory
+ @param[in] size
+ The buffer size in bytes
+ @param[in] overwritable
+ Set to TRUE is the FIFO is overwritable when the FIFO
+ is full (the first element will be overwritten)
+ @param[in] irq
+ The IRQ number to disable for MUTEX protection.
+ Set the -1 if not required.
+*/
+/**************************************************************************/
+void fifo_init(fifo_t* f, uint8_t* buffer, uint16_t size, bool overwritable, IRQn_Type irq)
+{
+ f->buf = buffer;
+ f->size = size;
+ f->rd_ptr = f->wr_ptr = f->len = 0;
+ f->overwritable = overwritable;
+ f->irq = irq;
+}
+
+/**************************************************************************/
+/*!
+ @brief Read one byte out of the RX buffer.
+
+ This function will return the byte located at the array index of the
+ read pointer, and then increment the read pointer index. If the read
+ pointer exceeds the maximum buffer size, it will roll over to zero.
+
+ @param[in] f
+ Pointer to the FIFO buffer to manipulate
+ @param[in] data
+ Pointer to the place holder for data read from the buffer
+
+ @returns TRUE if the queue is not empty
+*/
+/**************************************************************************/
+bool fifo_read(fifo_t* f, uint8_t *data)
+{
+ if (fifo_isEmpty(f))
+ return false;
+
+ mutex_lock(f);
+
+ *data = f->buf[f->rd_ptr];
+ f->rd_ptr = (f->rd_ptr + 1) % f->size;
+ f->len--;
+
+ mutex_unlock(f);
+
+ return true;
+}
+
+/**************************************************************************/
+/*!
+ @brief Read a byte array from FIFO
+
+ @param[in] f
+ Pointer to the FIFO buffer to manipulate
+ @param[in] rx
+ Pointer to the place holder for data read from the buffer
+ @param[in] maxlen
+ The maximum number of bytes to read from the FIFO
+
+ @returns The actual number of bytes read from the FIFO
+ */
+/**************************************************************************/
+uint16_t fifo_readArray(fifo_t* f, uint8_t* rx, uint16_t maxlen)
+{
+ uint16_t len = 0;
+
+ while ( len < maxlen && fifo_read(f, rx) )
+ {
+ len++;
+ rx++;
+ }
+
+ return len;
+}
+
+/**************************************************************************/
+/*!
+ @brief Write one byte into the RX buffer.
+
+ This function will write one byte into the array index specified by
+ the write pointer and increment the write index. If the write index
+ exceeds the max buffer size, then it will roll over to zero.
+
+ @param[in] f
+ Pointer to the FIFO buffer to manipulate
+ @param[in] data
+ The byte to add to the FIFO
+
+ @returns TRUE if the data was written to the FIFO (overwrittable
+ FIFO will always return TRUE)
+*/
+/**************************************************************************/
+bool fifo_write(fifo_t* f, uint8_t data)
+{
+ if ( fifo_isFull(f) && f->overwritable == false)
+ return false;
+
+ mutex_lock(f);
+
+ f->buf[f->wr_ptr] = data;
+ f->wr_ptr = (f->wr_ptr + 1) % f->size;
+
+ if (fifo_isFull(f))
+ {
+ f->rd_ptr = f->wr_ptr; // keep the full state (rd == wr && len = size)
+ }else
+ {
+ f->len++;
+ }
+
+ mutex_unlock(f);
+
+ return true;
+}
+
+/**************************************************************************/
+/*!
+ @brief Clear the fifo read and write pointers and set length to zero
+
+ @param[in] f
+ Pointer to the FIFO buffer to manipulate
+*/
+/**************************************************************************/
+void fifo_clear(fifo_t *f)
+{
+ mutex_lock(f);
+
+ f->rd_ptr = 0;
+ f->wr_ptr = 0;
+ f->len = 0;
+
+ mutex_unlock(f);
+}
diff --git a/tinyusb/common/fifo.h b/tinyusb/common/fifo.h
new file mode 100644
index 000000000..1019c8bde
--- /dev/null
+++ b/tinyusb/common/fifo.h
@@ -0,0 +1,76 @@
+/*
+ * fifo.h
+ *
+ * Created on: Nov 27, 2012
+ * Author: hathach (thachha@live.com)
+ */
+
+/*
+ * Software License Agreement (BSD License)
+ * Copyright (c) 2012, hathach (thachha@live.com)
+ * All rights reserved.
+ *
+ * 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.
+ *
+ * This file is part of the tiny usb stack.
+ */
+
+#ifndef _TUSB_FIFO_H_
+#define _TUSB_FIFO_H_
+
+#include "common/common.h"
+
+/* ToDo: Describe each field in fifo_t */
+typedef struct _fifo_t
+{
+ uint8_t* buf;
+ uint16_t size;
+ volatile uint16_t len;
+ volatile uint16_t wr_ptr;
+ volatile uint16_t rd_ptr;
+ bool overwritable;
+ IRQn_Type irq;
+} fifo_t;
+
+void fifo_init(fifo_t* f, uint8_t* buffer, uint16_t size, bool overwritable, IRQn_Type irq);
+bool fifo_write(fifo_t* f, uint8_t data);
+bool fifo_read(fifo_t* f, uint8_t *data);
+uint16_t fifo_readArray(fifo_t* f, uint8_t * rx, uint16_t maxlen);
+void fifo_clear(fifo_t*);
+
+static inline bool fifo_isEmpty(fifo_t* f)
+{
+ return (f->len == 0);
+}
+
+static inline bool fifo_isFull(fifo_t* f)
+{
+ return (f->len == f->size);
+}
+
+static inline uint16_t fifo_getLength(fifo_t* f)
+{
+ return f->len;
+}
+
+#endif /* _TUSB_FIFO_H_ */
diff --git a/tinyusb/device/dcd.c b/tinyusb/device/dcd.c
index 4ae826597..11f920b13 100644
--- a/tinyusb/device/dcd.c
+++ b/tinyusb/device/dcd.c
@@ -40,20 +40,58 @@
// TODO refractor later
#include "descriptors.h"
+#define USB_ROM_SIZE (1024*2)
+uint8_t usb_RomDriver_buffer[USB_ROM_SIZE]ALIGNED(2048) /*__BSS(RAM2)*/;
+USBD_HANDLE_T g_hUsb;
+volatile static bool isConfigured = false;
+/**************************************************************************/
+/*!
+ @brief Handler for the USB Configure Event
+*/
+/**************************************************************************/
+ErrorCode_t USB_Configure_Event (USBD_HANDLE_T hUsb)
+{
+ USB_CORE_CTRL_T* pCtrl = (USB_CORE_CTRL_T*)hUsb;
+ if (pCtrl->config_value)
+ {
+ #if defined(CLASS_HID)
+ ASSERT_STATUS( usb_hid_configured(hUsb) );
+ #endif
+
+ #ifdef CFG_USB_CDC
+ ASSERT_STATUS( usb_cdc_configured(hUsb) );
+ #endif
+ }
+
+ isConfigured = true;
+
+ return LPC_OK;
+}
+
+/**************************************************************************/
+/*!
+ @brief Handler for the USB Reset Event
+*/
+/**************************************************************************/
+ErrorCode_t USB_Reset_Event (USBD_HANDLE_T hUsb)
+{
+ isConfigured = false;
+ return LPC_OK;
+}
void dcd_init()
{
- /* ROM DRIVER INIT */
+ /* ROM DRIVER INIT */
USBD_API_INIT_PARAM_T usb_param =
{
-// .usb_reg_base = LPC_USB_BASE,
-// .max_num_ep = USB_MAX_EP_NUM,
-// .mem_base = (uint32_t) usb_RomDriver_buffer,
-// .mem_size = USB_ROM_SIZE, //USBD_API->hw->GetMemSize()
-//
-// .USB_Configure_Event = USB_Configure_Event,
-// .USB_Reset_Event = USB_Reset_Event
+ .usb_reg_base = LPC_USB_BASE,
+ .max_num_ep = USB_MAX_EP_NUM,
+ .mem_base = (uint32_t) usb_RomDriver_buffer,
+ .mem_size = USB_ROM_SIZE, //USBD_API->hw->GetMemSize()
+
+ .USB_Configure_Event = USB_Configure_Event,
+ .USB_Reset_Event = USB_Reset_Event
};
USB_CORE_DESCS_T DeviceDes =
@@ -65,7 +103,50 @@ void dcd_init()
.device_qualifier = NULL
};
- USBD_HANDLE_T g_hUsb;
/* Start USB hardware initialisation */
ASSERT_STATUS(USBD_API->hw->Init(&g_hUsb, &DeviceDes, &usb_param));
+
+ /* Initialise the class driver(s) */
+ #ifdef CFG_USB_CDC
+ ASSERT_STATUS( usb_cdc_init(g_hUsb, &USB_FsConfigDescriptor.CDC_CCI_Interface,
+ &USB_FsConfigDescriptor.CDC_DCI_Interface, &usb_param.mem_base, &usb_param.mem_size) );
+ #endif
+
+ #ifdef CFG_CLASS_HID_KEYBOARD
+ ASSERT_STATUS( usb_hid_init(g_hUsb , &USB_FsConfigDescriptor.HID_KeyboardInterface ,
+ HID_KeyboardReportDescriptor, USB_FsConfigDescriptor.HID_KeyboardHID.DescriptorList[0].wDescriptorLength,
+ &usb_param.mem_base , &usb_param.mem_size) );
+ #endif
+
+ #ifdef CFG_USB_HID_MOUSE
+ ASSERT_STATUS( usb_hid_init(g_hUsb , &USB_FsConfigDescriptor.HID_MouseInterface ,
+ HID_MouseReportDescriptor, USB_FsConfigDescriptor.HID_MouseHID.DescriptorList[0].wDescriptorLength,
+ &usb_param.mem_base , &usb_param.mem_size) );
+ #endif
+
+ /* Enable the USB interrupt */
+ NVIC_EnableIRQ(USB_IRQ_IRQn);
+
+ /* Perform USB soft connect */
+ USBD_API->hw->Connect(g_hUsb, 1);
+}
+
+/**************************************************************************/
+/*!
+ @brief Indicates whether USB is configured or not
+*/
+/**************************************************************************/
+bool usb_isConfigured(void)
+{
+ return isConfigured;
+}
+
+/**************************************************************************/
+/*!
+ @brief Redirect the USB IRQ handler to the ROM handler
+*/
+/**************************************************************************/
+void USB_IRQHandler(void)
+{
+ USBD_API->hw->ISR(g_hUsb);
}
diff --git a/tinyusb/tusb_cfg.h b/tinyusb/tusb_cfg.h
index deeb8e425..7331d904f 100644
--- a/tinyusb/tusb_cfg.h
+++ b/tinyusb/tusb_cfg.h
@@ -47,9 +47,9 @@
#define CFG_TUSB_HOST
#define CFG_TUSB_DEVICE
-#define CFG_USB_HID_KEYBOARD
+#define CFG_CLASS_HID_KEYBOARD
-#define CLASS_HID (defined CFG_USB_HID_KEYBOARD)
+#define CLASS_HID (defined CFG_CLASS_HID_KEYBOARD)
// TODO APP