diff --git a/demos/device/keyboard/.cproject b/demos/device/keyboard/.cproject
index c0236fe42..955991d7c 100644
--- a/demos/device/keyboard/.cproject
+++ b/demos/device/keyboard/.cproject
@@ -82,7 +82,7 @@
-
+
@@ -170,7 +170,7 @@
-
+
@@ -260,7 +260,7 @@
-
+
@@ -349,7 +349,7 @@
-
+
diff --git a/demos/device/keyboard/tusb_config.h b/demos/device/keyboard/tusb_config.h
index 897936421..8e4b635a4 100644
--- a/demos/device/keyboard/tusb_config.h
+++ b/demos/device/keyboard/tusb_config.h
@@ -81,14 +81,16 @@
//--------------------------------------------------------------------+
// DEVICE CONFIGURATION
//--------------------------------------------------------------------+
+#define TUSB_CFG_DEVICE_USE_ROM_DRIVER 1
+
+//------------- descriptors -------------//
#define TUSB_CFG_DEVICE_STRING_MANUFACTURER "tinyusb.org"
#define TUSB_CFG_DEVICE_STRING_PRODUCT "Device Example"
#define TUSB_CFG_DEVICE_STRING_SERIAL "1234"
#define TUSB_CFG_DEVICE_VENDORID 0x1FC9 // NXP
//#define TUSB_CFG_DEVICE_PRODUCTID 0x4567
-
-#define TUSB_CFG_DEVICE_USE_ROM_DRIVER 1
+#define TUSB_CFG_DEVICE_CONTROL_PACKET_SIZE 64
//------------- CLASS -------------//
#define TUSB_CFG_DEVICE_HID_KEYBOARD 0
diff --git a/demos/device/keyboard/tusb_descriptors.c b/demos/device/keyboard/tusb_descriptors.c
index 584e3f398..f1a42aa9d 100644
--- a/demos/device/keyboard/tusb_descriptors.c
+++ b/demos/device/keyboard/tusb_descriptors.c
@@ -129,7 +129,7 @@ tusb_descriptor_device_t app_tusb_desc_device =
.bDeviceSubClass = 0x00,
.bDeviceProtocol = 0x00,
- .bMaxPacketSize0 = USB_MAX_PACKET0,
+ .bMaxPacketSize0 = TUSB_CFG_DEVICE_CONTROL_PACKET_SIZE,
.idVendor = TUSB_CFG_DEVICE_VENDORID,
.idProduct = TUSB_CFG_PRODUCT_ID,
diff --git a/tinyusb/common/binary.h b/tinyusb/common/binary.h
index 78305ea60..260175976 100644
--- a/tinyusb/common/binary.h
+++ b/tinyusb/common/binary.h
@@ -70,9 +70,9 @@
#if defined(__GNUC__) && !defined(__CC_ARM)
-#define BIN8(x) (0b##x)
-#define BIN16(b1, b2) (0b##b1##b2)
-#define BIN32(b1, b2, b3, b4) (0b##b1##b2##b3##b4)
+#define BIN8(x) ((uint8_t) (0b##x))
+#define BIN16(b1, b2) ((uint16_t) (0b##b1##b2))
+#define BIN32(b1, b2, b3, b4) ((uint32_t) (0b##b1##b2##b3##b4))
#else
diff --git a/tinyusb/core/tusb_types.h b/tinyusb/core/tusb_types.h
index 75705dbe3..35cb07cd8 100644
--- a/tinyusb/core/tusb_types.h
+++ b/tinyusb/core/tusb_types.h
@@ -194,7 +194,10 @@ typedef enum {
TUSB_EVENT_XFER_COMPLETE,
TUSB_EVENT_XFER_ERROR,
TUSB_EVENT_INTERFACE_OPEN,
- TUSB_EVENT_INTERFACE_CLOSE
+ TUSB_EVENT_INTERFACE_CLOSE,
+
+ TUSB_EVENT_BUS_RESET, // TODO refractor
+ TUSB_EVENT_SETUP_RECEIVED,
}tusb_event_t;
enum {
diff --git a/tinyusb/device/dcd.h b/tinyusb/device/dcd.h
index be139b713..b6d2f6bd5 100644
--- a/tinyusb/device/dcd.h
+++ b/tinyusb/device/dcd.h
@@ -62,6 +62,10 @@ tusb_error_t dcd_controller_reset(uint8_t coreid) ATTR_WARN_UNUSED_RESULT;
void dcd_controller_connect(uint8_t coreid);
void dcd_isr(uint8_t coreid);
+void dcd_pipe_control_write_zero_length(uint8_t coreid);
+tusb_error_t dcd_endpoint_configure(uint8_t coreid, tusb_descriptor_endpoint_t const * p_endpoint_desc) ATTR_WARN_UNUSED_RESULT;
+void dcd_device_set_address(uint8_t coreid, uint8_t dev_addr);
+
#ifdef __cplusplus
}
#endif
diff --git a/tinyusb/device/dcd_lpc175x_6x.c b/tinyusb/device/dcd_lpc175x_6x.c
index 88ecb1529..19367a88f 100644
--- a/tinyusb/device/dcd_lpc175x_6x.c
+++ b/tinyusb/device/dcd_lpc175x_6x.c
@@ -47,6 +47,7 @@
//--------------------------------------------------------------------+
#include "dcd.h"
#include "dcd_lpc175x_6x.h"
+#include "usbd_dcd.h"
//--------------------------------------------------------------------+
// MACRO CONSTANT TYPEDEF
@@ -56,22 +57,192 @@ STATIC_ dcd_dma_descriptor_t* dcd_udca[32] ATTR_ALIGNED(128) TUSB_CFG_ATTR_USBRA
//--------------------------------------------------------------------+
// INTERNAL OBJECT & FUNCTION DECLARATION
//--------------------------------------------------------------------+
+static inline void endpoint_set_max_packet_size(uint8_t endpoint_idx, uint16_t max_packet_size) ATTR_ALWAYS_INLINE;
+static inline void endpoint_set_max_packet_size(uint8_t endpoint_idx, uint16_t max_packet_size)
+{
+ LPC_USB->USBEpInd = endpoint_idx; // select index before setting packet size
+ LPC_USB->USBMaxPSize = max_packet_size;
+}
+
+static inline void sie_commamd_code (uint8_t phase, uint8_t code_data) ATTR_ALWAYS_INLINE;
+static inline void sie_commamd_code (uint8_t phase, uint8_t code_data)
+{
+ LPC_USB->USBDevIntClr = (DEV_INT_COMMAND_CODE_EMPTY_MASK | DEV_INT_COMMAND_DATA_FULL_MASK);
+ LPC_USB->USBCmdCode = (phase << 8) | (code_data << 16);
+
+ uint32_t const wait_flag = (phase == SIE_CMDPHASE_READ) ? DEV_INT_COMMAND_DATA_FULL_MASK : DEV_INT_COMMAND_CODE_EMPTY_MASK;
+ while ((LPC_USB->USBDevIntSt & wait_flag) == 0); // TODO blocking forever potential
+ LPC_USB->USBDevIntClr = wait_flag;
+}
+
+static inline void sie_command_write (uint8_t cmd_code, uint8_t data_len, uint8_t data) ATTR_ALWAYS_INLINE;
+static inline void sie_command_write (uint8_t cmd_code, uint8_t data_len, uint8_t data)
+{
+ sie_commamd_code(SIE_CMDPHASE_COMMAND, cmd_code);
+
+ if (data_len)
+ {
+ sie_commamd_code(SIE_CMDPHASE_WRITE, data);
+ }
+}
+
+static inline uint32_t sie_command_read (uint8_t cmd_code, uint8_t data_len) ATTR_ALWAYS_INLINE;
+static inline uint32_t sie_command_read (uint8_t cmd_code, uint8_t data_len)
+{
+ // TODO multiple read
+ sie_commamd_code(SIE_CMDPHASE_READ, cmd_code);
+ return LPC_USB->USBCmdData;
+}
//--------------------------------------------------------------------+
// IMPLEMENTATION
//--------------------------------------------------------------------+
+void endpoint_control_isr(uint8_t coreid)
+{
+ (void) coreid; // suppress compiler warning
+ uint32_t const endpoint_int_status = LPC_USB->USBEpIntSt & LPC_USB->USBEpIntEn;
+
+ // control OUT
+ if (endpoint_int_status & BIT_(0))
+ {
+ uint32_t const endpoint_status = sie_command_read(SIE_CMDCODE_ENDPOINT_SELECT+0, 1);
+ if (endpoint_status & SIE_ENDPOINT_STATUS_SETUP_RECEIVED_MASK)
+ {
+ (void) sie_command_read(SIE_CMDCODE_ENDPOINT_SELECT_CLEAR_INTERRUPT+0, 1); // clear setup bit
+
+ // read endpoint
+ LPC_USB->USBCtrl = SLAVE_CONTROL_READ_ENABLE_MASK; // logical endpoint = 0
+ while ((LPC_USB->USBRxPLen & SLAVE_RXPLEN_PACKET_READY_MASK) == 0) {}
+
+ ASSERT_INT(8, LPC_USB->USBRxPLen & SLAVE_RXPLEN_PACKET_LENGTH_MASK, (void) 0);
+
+ uint32_t *p_setup = (uint32_t*) &usbd_devices[0].setup_packet;
+ *p_setup = LPC_USB->USBRxData;
+ p_setup += 4;
+ *p_setup = LPC_USB->USBRxData;
+ // TODO setup received callback
+ usbd_isr(0, TUSB_EVENT_SETUP_RECEIVED);
+ }else
+ {
+// ASSERT(false, (void) 0); // not current supported
+ }
+
+ sie_command_write(SIE_CMDCODE_BUFFER_CLEAR, 0, 0);
+ }
+
+ // control IN
+ if (endpoint_int_status & BIT_(1))
+ {
+
+ }
+
+ LPC_USB->USBEpIntClr = endpoint_int_status; // acknowledge interrupt
+}
+
void dcd_isr(uint8_t coreid)
{
+ uint32_t device_int_status = LPC_USB->USBDevIntSt & LPC_USB->USBDevIntEn & DEV_INT_ALL_MASK;
+ LPC_USB->USBDevIntClr = device_int_status;// Acknowledge handled interrupt
+
+ //------------- usb bus event -------------//
+ if (device_int_status & DEV_INT_DEVICE_STATUS_MASK)
+ {
+ uint32_t dev_status_reg = sie_command_read(SIE_CMDCODE_DEVICE_STATUS, 1);
+ if (dev_status_reg & SIE_DEV_STATUS_RESET_MASK)
+ {
+ usbd_isr(coreid, TUSB_EVENT_BUS_RESET);
+ }
+
+ // TODO invoke some callbacks
+ if (dev_status_reg & SIE_DEV_STATUS_CONNECT_CHANGE_MASK)
+ {
+
+ }
+ if (dev_status_reg & SIE_DEV_STATUS_SUSPEND_CHANGE_MASK)
+ {
+
+ }
+ }
+
+ //------------- slave mode, control endpoint -------------//
+ if (device_int_status & DEV_INT_ENDPOINT_SLOW_MASK)
+ {
+ // only occur on control endpoint, all other use DMA
+ endpoint_control_isr(coreid);
+ }
+
+ if (device_int_status & DEV_INT_ERROR_MASK)
+ {
+ ASSERT(false, (void) 0);
+ }
}
+//--------------------------------------------------------------------+
+// USBD-DCD API
+//--------------------------------------------------------------------+
tusb_error_t dcd_init(void)
+{
+ //------------- user manual 11.13 usb device controller initialization -------------// LPC_USB->USBEpInd = 0;
+ // step 6 : set up control endpoint
+ endpoint_set_max_packet_size(0, TUSB_CFG_DEVICE_CONTROL_PACKET_SIZE);
+ endpoint_set_max_packet_size(1, TUSB_CFG_DEVICE_CONTROL_PACKET_SIZE);
+ while ((LPC_USB->USBDevIntSt & DEV_INT_ENDPOINT_REALIZED_MASK) == 0);
+
+ // step 7 : slave mode set up
+ LPC_USB->USBEpIntEn = (uint32_t) BIN8(11); // control endpoint cannot use DMA, non-control all use DMA
+
+ LPC_USB->USBDevIntEn = (DEV_INT_DEVICE_STATUS_MASK | DEV_INT_ENDPOINT_SLOW_MASK | DEV_INT_ERROR_MASK);
+ LPC_USB->USBDevIntClr = 0xFFFFFFFF; // clear all pending interrupt
+
+ LPC_USB->USBEpIntClr = 0xFFFFFFFF; // clear all pending interrupt
+ LPC_USB->USBEpIntPri = 0; // same priority for all endpoint
+
+ // step 8 : DMA set up
+ LPC_USB->USBEpDMADis = 0xFFFFFFFF; // firstly disable all dma
+ LPC_USB->USBDMARClr = 0xFFFFFFFF; // clear all pending interrupt
+ LPC_USB->USBEoTIntClr = 0xFFFFFFFF;
+ LPC_USB->USBNDDRIntClr = 0xFFFFFFFF;
+ LPC_USB->USBSysErrIntClr = 0xFFFFFFFF;
+
+ for (uint8_t index = 0; index < DCD_MAX_DD; index++)
+ {
+ dcd_udca[index] = 0;
+ }
+ LPC_USB->USBUDCAH = (uint32_t) dcd_udca;
+ LPC_USB->USBDMAIntEn = (DMA_INT_END_OF_XFER_MASK | DMA_INT_NEW_DD_REQUEST_MASK | DMA_INT_ERROR_MASK );
+
+ // clear all stall on control endpoint IN & OUT if any
+ sie_command_write(SIE_CMDCODE_ENDPOINT_SET_STATUS , 0, 0);
+ sie_command_write(SIE_CMDCODE_ENDPOINT_SET_STATUS + 1, 0, 0);
+
+ return TUSB_ERROR_NONE;
+}
+
+tusb_error_t dcd_endpoint_configure(uint8_t coreid, tusb_descriptor_endpoint_t const * p_endpoint_desc)
{
return TUSB_ERROR_NONE;
}
void dcd_controller_connect(uint8_t coreid)
{
-
+ sie_command_write(SIE_CMDCODE_DEVICE_STATUS, 1, 1);
}
+
+void dcd_device_set_address(uint8_t coreid, uint8_t dev_addr)
+{
+ sie_command_write(SIE_CMDCODE_SET_ADDRESS, 1, 0x80 | dev_addr); // 7th bit is : device_enable
+}
+
+void dcd_pipe_control_write_zero_length(uint8_t coreid)
+{
+ LPC_USB->USBCtrl = SLAVE_CONTROL_WRITE_ENABLE_MASK; // logical endpoint = 0
+ LPC_USB->USBTxPLen = 0;
+
+ LPC_USB->USBCtrl = 0;
+
+ sie_command_write(SIE_CMDCODE_ENDPOINT_SELECT+1, 0, 0); // select control IN endpoint
+ sie_command_write(SIE_CMDCODE_BUFFER_VALIDATE, 0, 0);
+}
+
#endif
diff --git a/tinyusb/device/dcd_lpc175x_6x.h b/tinyusb/device/dcd_lpc175x_6x.h
index b5e591b58..fac7c8ddf 100644
--- a/tinyusb/device/dcd_lpc175x_6x.h
+++ b/tinyusb/device/dcd_lpc175x_6x.h
@@ -83,12 +83,111 @@ typedef struct
// uint32_t iso_packet_size_addr; // iso only, can be omitted for non-iso
} ATTR_ALIGNED(4) dcd_dma_descriptor_t;
-#define DCD_DD_NUM 10 // TODO scale with configure
+#define DCD_MAX_DD 10 // TODO scale with configure
typedef struct {
- dcd_dma_descriptor_t dd[DCD_DD_NUM];
+ dcd_dma_descriptor_t dd[DCD_MAX_DD];
}dcd_data_t;
+//--------------------------------------------------------------------+
+// Register Interface
+//--------------------------------------------------------------------+
+
+//------------- USB Interrupt USBIntSt -------------//
+//enum {
+// DCD_USB_REQ_LOW_PRIO_MASK = BIT_(0),
+// DCD_USB_REQ_HIGH_PRIO_MASK = BIT_(1),
+// DCD_USB_REQ_DMA_MASK = BIT_(2),
+// DCD_USB_REQ_NEED_CLOCK_MASK = BIT_(8),
+// DCD_USB_REQ_ENABLE_MASK = BIT_(31)
+//};
+
+//------------- Device Interrupt USBDevInt -------------//
+enum {
+ DEV_INT_FRAME_MASK = BIT_(0),
+ DEV_INT_ENDPOINT_FAST_MASK = BIT_(1),
+ DEV_INT_ENDPOINT_SLOW_MASK = BIT_(2),
+ DEV_INT_DEVICE_STATUS_MASK = BIT_(3),
+ DEV_INT_COMMAND_CODE_EMPTY_MASK = BIT_(4),
+ DEV_INT_COMMAND_DATA_FULL_MASK = BIT_(5),
+ DEV_INT_RX_ENDPOINT_PACKET_MASK = BIT_(6),
+ DEV_INT_TX_ENDPOINT_PACKET_MASK = BIT_(7),
+ DEV_INT_ENDPOINT_REALIZED_MASK = BIT_(8),
+ DEV_INT_ERROR_MASK = BIT_(9),
+
+ DEV_INT_ALL_MASK = DEV_INT_FRAME_MASK | DEV_INT_ENDPOINT_FAST_MASK | DEV_INT_ENDPOINT_SLOW_MASK |
+ DEV_INT_DEVICE_STATUS_MASK | DEV_INT_COMMAND_CODE_EMPTY_MASK | DEV_INT_COMMAND_DATA_FULL_MASK |
+ DEV_INT_RX_ENDPOINT_PACKET_MASK | DEV_INT_TX_ENDPOINT_PACKET_MASK | DEV_INT_ENDPOINT_REALIZED_MASK |
+ DEV_INT_ERROR_MASK
+};
+
+//------------- DMA Interrupt USBDMAInt-------------//
+enum {
+ DMA_INT_END_OF_XFER_MASK = BIT_(0),
+ DMA_INT_NEW_DD_REQUEST_MASK = BIT_(1),
+ DMA_INT_ERROR_MASK = BIT_(2)
+};
+
+//------------- USBCtrl -------------//
+enum {
+ SLAVE_CONTROL_READ_ENABLE_MASK = BIT_(0),
+ SLAVE_CONTROL_WRITE_ENABLE_MASK = BIT_(1),
+ SLAVE_CONTROL_READ_ENABLE_POS = 2
+};
+
+//------------- USBRxPLen -------------//
+enum {
+ SLAVE_RXPLEN_PACKET_LENGTH_MASK = (BIT_(10)-1),
+ SLAVE_RXPLEN_DATA_VALID_MASK = BIT_(10),
+ SLAVE_RXPLEN_PACKET_READY_MASK = BIT_(11),
+};
+
+//------------- SIE Command Code -------------//
+enum {
+ SIE_CMDPHASE_WRITE = 1,
+ SIE_CMDPHASE_READ = 2,
+ SIE_CMDPHASE_COMMAND = 5
+};
+
+enum {
+ // device commands
+ SIE_CMDCODE_SET_ADDRESS = 0xd0,
+ SIE_CMDCODE_CONFIGURE_DEVICE = 0xd8,
+ SIE_CMDCODE_SET_MODE = 0xf3,
+ SIE_CMDCODE_READ_FRAME_NUMBER = 0xf5,
+ SIE_CMDCODE_READ_TEST_REGISTER = 0xfd,
+ SIE_CMDCODE_DEVICE_STATUS = 0xfe,
+ SIE_CMDCODE_GET_ERROR = 0xff,
+ SIE_CMDCODE_READ_ERROR_STATUS = 0xfb,
+
+ // endpoint commands
+ SIE_CMDCODE_ENDPOINT_SELECT = 0x00, // + endpoint index
+ SIE_CMDCODE_ENDPOINT_SELECT_CLEAR_INTERRUPT = 0x40, // + endpoint index, should use USBEpIntClr instead
+ SIE_CMDCODE_ENDPOINT_SET_STATUS = 0x40, // + endpoint index
+ SIE_CMDCODE_BUFFER_CLEAR = 0xf2,
+ SIE_CMDCODE_BUFFER_VALIDATE = 0xfa
+};
+
+//------------- SIE Device Status (get/set from SIE_CMDCODE_DEVICE_STATUS) -------------//
+enum {
+ SIE_DEV_STATUS_CONNECT_MASK = BIT_(0),
+ SIE_DEV_STATUS_CONNECT_CHANGE_MASK = BIT_(1),
+ SIE_DEV_STATUS_SUSPEND_MASK = BIT_(2),
+ SIE_DEV_STATUS_SUSPEND_CHANGE_MASK = BIT_(3),
+ SIE_DEV_STATUS_RESET_MASK = BIT_(4)
+};
+
+//------------- SIE Endpoint Status -------------//
+enum {
+ SIE_ENDPOINT_STATUS_FULL_EMPTY_MASK = BIT_(0), // 0: empty, 1 full. IN endpoint checks empty, OUT endpoint check full
+ SIE_ENDPOINT_STATUS_STALL_MASK = BIT_(1),
+ SIE_ENDPOINT_STATUS_SETUP_RECEIVED_MASK = BIT_(2), // clear by SIE_CMDCODE_ENDPOINT_SELECT_CLEAR_INTERRUPT
+ SIE_ENDPOINT_STATUS_PACKET_OVERWRITTEN_MASK = BIT_(3), // previous packet is overwritten by a SETUP packet
+ SIE_ENDPOINT_STATUS_NAK_MASK = BIT_(4), // last packet response is NAK (auto clear by an ACK)
+ SIE_ENDPOINT_STATUS_BUFFER1_FULL_MASK = BIT_(5),
+ SIE_ENDPOINT_STATUS_BUFFER2_FULL_MASK = BIT_(6)
+};
+
#ifdef __cplusplus
}
#endif
diff --git a/tinyusb/device/usbd.c b/tinyusb/device/usbd.c
index 160302d99..8004e2bff 100644
--- a/tinyusb/device/usbd.c
+++ b/tinyusb/device/usbd.c
@@ -47,14 +47,12 @@
//--------------------------------------------------------------------+
#include "tusb.h"
#include "tusb_descriptors.h" // TODO callback include
+#include "usbd_dcd.h"
//--------------------------------------------------------------------+
// MACRO CONSTANT TYPEDEF
//--------------------------------------------------------------------+
-//typedef struct {
-// volatile uint8_t state;
-//
-//};
+usbd_device_info_t usbd_devices[CONTROLLER_DEVICE_NUMBER];
// TODO fix/compress number of class driver
static device_class_driver_t const usbh_class_drivers[TUSB_CLASS_MAX_CONSEC_NUMBER] =
@@ -79,6 +77,47 @@ static tusb_error_t usbd_string_descriptor_init(void);
//
//}
+void usbd_bus_reset(uint32_t coreid)
+{
+ memclr_(usbd_devices, sizeof(usbd_device_info_t)*CONTROLLER_DEVICE_NUMBER);
+}
+
+void std_get_descriptor(uint8_t coreid)
+{
+ tusb_std_descriptor_type_t const desc_type = usbd_devices[coreid].setup_packet.wValue >> 8;
+ uint8_t const desc_index = u16_low_u8( usbd_devices[coreid].setup_packet.wValue );
+ switch ( desc_type )
+ {
+ case TUSB_DESC_TYPE_DEVICE:
+
+ break;
+
+ default:
+ return;
+ }
+}
+
+void usbd_setup_received(uint8_t coreid)
+{
+ usbd_device_info_t *p_device = &usbd_devices[coreid];
+ switch ( p_device->setup_packet.bRequest)
+ {
+ case TUSB_REQUEST_GET_DESCRIPTOR:
+ std_get_descriptor(coreid);
+ break;
+
+ case TUSB_REQUEST_SET_ADDRESS:
+ p_device->address = (uint8_t) p_device->setup_packet.wValue;
+ dcd_device_set_address(coreid, p_device->address);
+ break;
+
+ default:
+ return;
+ }
+
+// dcd_pipe_control_write_zero_length(coreid);
+}
+
//--------------------------------------------------------------------+
// IMPLEMENTATION
//--------------------------------------------------------------------+
@@ -89,7 +128,6 @@ tusb_error_t usbd_init (void)
ASSERT_STATUS ( dcd_init() );
uint16_t length = 0;
-
#if TUSB_CFG_DEVICE_HID_KEYBOARD
ASSERT_STATUS( hidd_init(&app_tusb_desc_configuration.keyboard_interface, &length) );
#endif
@@ -98,6 +136,8 @@ tusb_error_t usbd_init (void)
ASSERT_STATUS( hidd_init(&app_tusb_desc_configuration.mouse_interface, &length) );
#endif
+ usbd_bus_reset(0);
+
#ifndef _TEST_
hal_interrupt_enable(0); // TODO USB1
#endif
@@ -109,6 +149,28 @@ tusb_error_t usbd_init (void)
#endif
+
+//--------------------------------------------------------------------+
+// callback from DCD ISR
+//--------------------------------------------------------------------+
+void usbd_isr(uint8_t coreid, tusb_event_t event)
+{
+ switch(event)
+ {
+ case TUSB_EVENT_BUS_RESET:
+ usbd_bus_reset(coreid);
+ break;
+
+ case TUSB_EVENT_SETUP_RECEIVED:
+ usbd_setup_received(coreid);
+ break;
+
+ default:
+ ASSERT(false, (void) 0);
+ break;
+ }
+}
+
//--------------------------------------------------------------------+
// HELPER
//--------------------------------------------------------------------+
diff --git a/tinyusb/device/usbd_dcd.h b/tinyusb/device/usbd_dcd.h
new file mode 100644
index 000000000..eb0f1da63
--- /dev/null
+++ b/tinyusb/device/usbd_dcd.h
@@ -0,0 +1,77 @@
+/**************************************************************************/
+/*!
+ @file usbd_dcd.h
+ @author hathach (tinyusb.org)
+
+ @section LICENSE
+
+ Software License Agreement (BSD License)
+
+ Copyright (c) 2013, hathach (tinyusb.org)
+ 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. Neither the name of the copyright holders nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''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 COPYRIGHT HOLDER 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 tinyusb stack.
+*/
+/**************************************************************************/
+
+/** \ingroup TBD
+ * \defgroup TBD
+ * \brief TBD
+ *
+ * @{
+ */
+
+#ifndef _TUSB_USBD_DCD_H_
+#define _TUSB_USBD_DCD_H_
+
+//--------------------------------------------------------------------+
+// INCLUDE
+//--------------------------------------------------------------------+
+#include "common/common.h"
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+typedef struct {
+ volatile uint8_t state;
+ uint8_t address;
+ tusb_std_request_t setup_packet;
+
+}usbd_device_info_t;
+
+extern usbd_device_info_t usbd_devices[CONTROLLER_DEVICE_NUMBER];
+//--------------------------------------------------------------------+
+// callback from DCD ISR
+//--------------------------------------------------------------------+
+void usbd_isr(uint8_t coreid, tusb_event_t event);
+
+#ifdef __cplusplus
+ }
+#endif
+
+#endif /* _TUSB_USBD_DCD_H_ */
+
+/** @} */
diff --git a/tinyusb/hal/hal_lpc175x_6x.c b/tinyusb/hal/hal_lpc175x_6x.c
index 82ba772d1..3f1b2a357 100644
--- a/tinyusb/hal/hal_lpc175x_6x.c
+++ b/tinyusb/hal/hal_lpc175x_6x.c
@@ -46,11 +46,16 @@
#include "common/common.h"
#include "hal.h"
+enum {
+ PCONP_PCUSB = 31
+};
+
//--------------------------------------------------------------------+
// IMPLEMENTATION
//--------------------------------------------------------------------+
tusb_error_t hal_init(void)
{
+ //------------- user manual 11.13 usb device controller initialization -------------//
// TODO remove magic number
/* Enable AHB clock to the USB block and USB RAM. */
// LPC_SYSCON->SYSAHBCLKCTRL |= ((0x1<<14) | (0x1<<27));
@@ -61,7 +66,7 @@ tusb_error_t hal_init(void)
// LPC_PINCON->PINSEL3 &= ~(3<<6); TODO HOST
// LPC_PINCON->PINSEL3 |= (2<<6);
- LPC_SC->PCONP |= (1UL<<31); /* USB PCLK -> enable USB Per.*/
+ LPC_SC->PCONP |= BIT_(PCONP_PCUSB); /* USB PCLK -> enable USB Per.*/
// DEVICE mode
LPC_USB->USBClkCtrl = 0x12; /* Dev, PortSel, AHB clock enable */
diff --git a/tinyusb/hal/hal_lpc175x_6x.h b/tinyusb/hal/hal_lpc175x_6x.h
index e57048e14..3b94b23c3 100644
--- a/tinyusb/hal/hal_lpc175x_6x.h
+++ b/tinyusb/hal/hal_lpc175x_6x.h
@@ -52,6 +52,9 @@
#include "LPC17xx.h"
+//--------------------------------------------------------------------+
+//
+//--------------------------------------------------------------------+
static inline void hal_interrupt_enable(uint8_t controller_id)
{
(void) controller_id; // discard compiler's warning
diff --git a/tinyusb/tusb_option.h b/tinyusb/tusb_option.h
index f2e693b9a..025d3a0af 100644
--- a/tinyusb/tusb_option.h
+++ b/tinyusb/tusb_option.h
@@ -172,9 +172,6 @@
#define USB_FS_MAX_BULK_PACKET 64
#define USB_HS_MAX_BULK_PACKET USB_FS_MAX_BULK_PACKET /* Full speed device only */
-// Control Endpoint
-#define USB_MAX_PACKET0 64
-
/* HID In/Out Endpoint Address */
#define HID_KEYBOARD_EP_IN ENDPOINT_IN_LOGICAL_TO_PHYSICAL(1)
#define HID_MOUSE_EP_IN ENDPOINT_IN_LOGICAL_TO_PHYSICAL(4)