Merge pull request #194 from cr1901/msp430f5529

[WIP] MSP430 Support
This commit is contained in:
Ha Thach 2020-03-24 11:57:20 +07:00 committed by GitHub
commit 95009a9e79
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 933 additions and 14 deletions

View File

@ -39,8 +39,11 @@ jobs:
npm install --global xpm
xpm install --global @xpack-dev-tools/arm-none-eabi-gcc@latest
xpm install --global @xpack-dev-tools/riscv-none-embed-gcc@latest
wget http://software-dl.ti.com/msp430/msp430_public_sw/mcu/msp430/MSPGCC/8_3_0_0/exports/msp430-gcc-8.3.0.16_linux64.tar.bz2 -O /tmp/msp430-gcc.tar.bz2
tar -C $HOME -xaf /tmp/msp430-gcc.tar.bz2
echo "::add-path::`echo $HOME/opt/xPacks/@xpack-dev-tools/arm-none-eabi-gcc/*/.content/bin`"
echo "::add-path::`echo $HOME/opt/xPacks/@xpack-dev-tools/riscv-none-embed-gcc/*/.content/bin`"
echo "::add-path::`echo $HOME/msp430-gcc-*_linux64/bin`"
- name: Checkout TinyUSB
uses: actions/checkout@v2

View File

@ -64,7 +64,9 @@
// DEVICE CONFIGURATION
//--------------------------------------------------------------------
#ifndef CFG_TUD_ENDPOINT0_SIZE
#define CFG_TUD_ENDPOINT0_SIZE 64
#endif
//------------- CLASS -------------//
#define CFG_TUD_CDC 0

View File

@ -51,7 +51,9 @@
// DEVICE CONFIGURATION
//--------------------------------------------------------------------
#ifndef CFG_TUD_ENDPOINT0_SIZE
#define CFG_TUD_ENDPOINT0_SIZE 64
#endif
//------------- CLASS -------------//

View File

@ -0,0 +1 @@
too many warnings for 16-bit integer overflow

View File

@ -17,6 +17,8 @@ INC += \
# Example source
EXAMPLE_SOURCE += $(wildcard src/*.c)
SRC_C += $(addprefix $(CURRENT_PATH)/, $(EXAMPLE_SOURCE))
# lwip sources
SRC_C += \
lib/lwip/src/core/altcp.c \
lib/lwip/src/core/altcp_alloc.c \

View File

@ -51,7 +51,9 @@
// DEVICE CONFIGURATION
//--------------------------------------------------------------------
#ifndef CFG_TUD_ENDPOINT0_SIZE
#define CFG_TUD_ENDPOINT0_SIZE 64
#endif
//------------- CLASS -------------//

View File

@ -3,10 +3,12 @@
#
# Compiler
ifeq ($(BOARD), fomu)
CROSS_COMPILE = riscv-none-embed-
ifeq ($(BOARD), msp_exp430f5529lp)
CROSS_COMPILE = msp430-elf-
else ifeq ($(BOARD), fomu)
CROSS_COMPILE = riscv-none-embed-
else
CROSS_COMPILE = arm-none-eabi-
CROSS_COMPILE = arm-none-eabi-
endif
CC = $(CROSS_COMPILE)gcc
CXX = $(CROSS_COMPILE)g++

View File

@ -30,10 +30,14 @@ INC += $(TOP)/src
#
CFLAGS += $(addprefix -I,$(INC))
LDFLAGS += $(CFLAGS) -fshort-enums -Wl,-T,$(TOP)/$(LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections -specs=nosys.specs -specs=nano.specs
ifeq ($(BOARD), msp_exp430f5529lp)
LDFLAGS += $(CFLAGS) -fshort-enums -Wl,-T,$(TOP)/$(LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections
else
LDFLAGS += $(CFLAGS) -fshort-enums -Wl,-T,$(TOP)/$(LD_FILE) -Wl,-Map=$@.map -Wl,-cref -Wl,-gc-sections -specs=nosys.specs -specs=nano.specs
endif
ASFLAGS += $(CFLAGS)
# Assembly files can be name with upper case .S, convert it to .s
# Assembly files can be name with upper case .S, convert it to .s
SRC_S := $(SRC_S:.S=.s)
# Due to GCC LTO bug https://bugs.launchpad.net/gcc-arm-embedded/+bug/1747966
@ -66,8 +70,8 @@ $(BUILD)/$(BOARD)-firmware.elf: $(OBJ)
$(BUILD)/$(BOARD)-firmware.bin: $(BUILD)/$(BOARD)-firmware.elf
@echo CREATE $@
@$(OBJCOPY) -O binary $^ $@
$(BUILD)/$(BOARD)-firmware.hex: $(BUILD)/$(BOARD)-firmware.elf
$(BUILD)/$(BOARD)-firmware.hex: $(BUILD)/$(BOARD)-firmware.elf
@echo CREATE $@
@$(OBJCOPY) -O ihex $^ $@
@ -114,7 +118,7 @@ clean:
# Flash binary using Jlink
ifeq ($(OS),Windows_NT)
JLINKEXE = JLink.exe
else
else
JLINKEXE = JLinkExe
endif

View File

@ -25,6 +25,13 @@
#include "board.h"
#if defined(__MSP430__)
#define sys_write write
#define sys_read read
#else
#define sys_write _write
#define sys_read _read
#endif
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
//--------------------------------------------------------------------+
@ -44,13 +51,13 @@
// newlib read()/write() retarget
TU_ATTR_USED int _write (int fhdl, const void *buf, size_t count)
TU_ATTR_USED int sys_write (int fhdl, const void *buf, size_t count)
{
(void) fhdl;
return board_uart_write(buf, count);
}
TU_ATTR_USED int _read (int fhdl, char *buf, size_t count)
TU_ATTR_USED int sys_read (int fhdl, char *buf, size_t count)
{
(void) fhdl;
return board_uart_read((uint8_t*) buf, count);

View File

@ -0,0 +1,33 @@
CFLAGS += \
-D__MSP430F5529__ \
-DCFG_TUSB_MCU=OPT_MCU_MSP430x5xx \
-DCFG_EXAMPLE_MSC_READONLY \
-DCFG_TUD_ENDPOINT0_SIZE=8
#-mmcu=msp430f5529
# All source paths should be relative to the top level.
LD_FILE = hw/mcu/ti/msp430/msp430-gcc-support-files/include/msp430f5529.ld
LDINC += $(TOP)/hw/mcu/ti/msp430/msp430-gcc-support-files/include
LDFLAGS += $(addprefix -L,$(LDINC))
INC += $(TOP)/hw/mcu/ti/msp430/msp430-gcc-support-files/include
# For TinyUSB port source
VENDOR = ti
CHIP_FAMILY = msp430x5xx
# export for libmsp430.so to same installation
ifneq ($(OS),Windows_NT)
export LD_LIBRARY_PATH=$(dir $(shell which MSP430Flasher))
endif
# flash target using TI MSP430-Flasher
# http://www.ti.com/tool/MSP430-FLASHER
# Please add its installation dir to PATH
flash: $(BUILD)/$(BOARD)-firmware.hex
MSP430Flasher -w $< -z [VCC]
# flash target using mspdebug.
flash-mspdebug: $(BUILD)/$(BOARD)-firmware.elf
$(MSPDEBUG) tilib "prog $<" --allow-fw-update

View File

@ -0,0 +1,214 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "msp430.h"
#define LED_PORT P1OUT
#define LED_PIN BIT0
#define LED_STATE_ON 1
#define BUTTON_PORT P1IN
#define BUTTON_PIN BIT1
#define BUTTON_STATE_ACTIVE 0
uint32_t cnt = 0;
static void SystemClock_Config(void)
{
WDTCTL = WDTPW + WDTHOLD; // Disable watchdog.
// Increase VCore to level 2- required for 16 MHz operation on this MCU.
PMMCTL0 = PMMPW + PMMCOREV_2;
UCSCTL3 = SELREF__XT2CLK; // FLL is fed by XT2.
// XT1 used for ACLK (default- not used in this demo)
P5SEL |= BIT4; // Required to enable XT1
// Loop until XT1 fault flag is cleared.
do
{
UCSCTL7 &= ~XT1LFOFFG;
}while(UCSCTL7 & XT1LFOFFG);
// XT2 is 4 MHz an external oscillator, use PLL to boost to 16 MHz.
P5SEL |= BIT2; // Required to enable XT2.
// Loop until XT2 fault flag is cleared
do
{
UCSCTL7 &= ~XT2OFFG;
}while(UCSCTL7 & XT2OFFG);
// Kickstart the DCO into the correct frequency range, otherwise a
// fault will occur.
// FIXME: DCORSEL_6 should work according to datasheet params, but generates
// a fault. I am not sure why it faults.
UCSCTL1 = DCORSEL_7;
UCSCTL2 = FLLD_2 + 3; // DCO freq = D * (N + 1) * (FLLREFCLK / n)
// DCOCLKDIV freq = (N + 1) * (FLLREFCLK / n)
// N = 3, D = 2, thus DCO freq = 32 MHz.
// MCLK configured for 16 MHz using XT2.
// SMCLK configured for 8 MHz using XT2.
UCSCTL4 |= SELM__DCOCLKDIV + SELS__DCOCLKDIV;
UCSCTL5 |= DIVM__16 + DIVS__2;
// Now wait till everything's stabilized.
do
{
UCSCTL7 &= ~(XT2OFFG + XT1LFOFFG + DCOFFG);
SFRIFG1 &= ~OFIFG;
}while(SFRIFG1 & OFIFG);
// Configure Timer A to use SMCLK as a source. Count 1000 ticks at 1 MHz.
TA0CCTL0 |= CCIE;
TA0CCR0 = 999; // 1000 ticks.
TA0CTL |= TASSEL_2 + ID_3 + MC__UP; // Use SMCLK, divide by 8, start timer.
// Initialize USB power and PLL.
USBKEYPID = USBKEY;
// VUSB enabled automatically.
// Wait two milliseconds to stabilize, per manual recommendation.
uint32_t ms_elapsed = board_millis();
do
{
while((board_millis() - ms_elapsed) < 2);
}while(!(USBPWRCTL & USBBGVBV));
// USB uses XT2 (4 MHz) directly. Enable the PLL.
USBPLLDIVB |= USBPLL_SETCLK_4_0;
USBPLLCTL |= (UPFDEN | UPLLEN);
// Wait until PLL locks. Check every 2ms, per manual.
ms_elapsed = board_millis();
do
{
USBPLLIR &= ~USBOOLIFG;
while((board_millis() - ms_elapsed) < 2);
}while(USBPLLIR & USBOOLIFG);
USBKEYPID = 0;
}
uint32_t wait = 0;
void board_init(void)
{
__bis_SR_register(GIE); // Enable interrupts.
SystemClock_Config();
// Enable basic I/O.
P1DIR |= LED_PIN; // LED output.
P1REN |= BUTTON_PIN; // Internal resistor enable.
P1OUT |= BUTTON_PIN; // Pullup.
// Enable the backchannel UART (115200)
P4DIR |= BIT5;
P4SEL |= (BIT5 | BIT4);
UCA1CTL1 |= (UCSSEL__SMCLK | UCSWRST); // Hold in reset, use SMCLK.
UCA1BRW = 4;
UCA1MCTL |= (UCBRF_3 | UCBRS_5 | UCOS16); // Overampling mode, 115200 baud.
// Copied from manual.
UCA1CTL1 &= ~UCSWRST;
// Set up USB pins.
USBKEYPID = USBKEY;
USBPHYCTL |= PUSEL; // Convert USB D+/D- pins to USB functionality.
USBKEYPID = 0;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
if(state)
{
LED_PORT |= LED_PIN;
}
else
{
LED_PORT &= ~LED_PIN;
}
}
uint32_t board_button_read(void)
{
return ((P1IN & BIT1) >> 1) == BUTTON_STATE_ACTIVE;
}
int board_uart_read(uint8_t * buf, int len)
{
for(int i = 0; i < len; i++)
{
// Wait until something to receive (cleared by reading buffer).
while(!(UCA1IFG & UCRXIFG));
buf[i] = UCA1RXBUF;
}
return len;
}
int board_uart_write(void const * buf, int len)
{
const char * char_buf = (const char *) buf;
for(int i = 0; i < len; i++)
{
// Wait until TX buffer is empty (cleared by writing buffer).
while(!(UCA1IFG & UCTXIFG));
UCA1TXBUF = char_buf[i];
}
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void __attribute__ ((interrupt(TIMER0_A0_VECTOR))) TIMER0_A0_ISR (void)
{
system_ticks++;
// TAxCCR0 CCIFG resets itself as soon as interrupt is invoked.
}
uint32_t board_millis(void)
{
uint32_t systick_mirror;
// 32-bit update is not atomic on MSP430. We can read the bottom 16-bits,
// an interrupt occurs, updates _all_ 32 bits, and then we return a
// garbage value. And I've seen it happen!
TA0CCTL0 &= ~CCIE;
systick_mirror = system_ticks;
TA0CCTL0 |= CCIE;
return systick_mirror;
}
#endif

View File

@ -44,6 +44,7 @@ typedef struct {
struct TU_ATTR_PACKED
{
volatile uint8_t connected : 1;
volatile uint8_t addressed : 1;
volatile uint8_t configured : 1;
volatile uint8_t suspended : 1;
@ -526,6 +527,7 @@ static bool process_control_request(uint8_t rhport, tusb_control_request_t const
usbd_control_set_request(p_request); // set request since DCD has no access to tud_control_status() API
dcd_set_address(rhport, (uint8_t) p_request->wValue);
// skip tud_control_status()
_usbd_dev.addressed = 1;
break;
case TUSB_REQ_GET_CONFIGURATION:
@ -793,7 +795,21 @@ static bool process_get_descriptor(uint8_t rhport, tusb_control_request_t const
switch(desc_type)
{
case TUSB_DESC_DEVICE:
return tud_control_xfer(rhport, p_request, (void*) tud_descriptor_device_cb(), sizeof(tusb_desc_device_t));
{
uint16_t len = sizeof(tusb_desc_device_t);
// Only send up to EP0 Packet Size if not addressed
// This only happens with the very first get device descriptor and EP0 size = 8 or 16.
if ((CFG_TUD_ENDPOINT0_SIZE < sizeof(tusb_desc_device_t)) && !_usbd_dev.addressed)
{
len = CFG_TUD_ENDPOINT0_SIZE;
// Hack here: we modify the request length to prevent usbd_control response with zlp
((tusb_control_request_t*) p_request)->wLength = CFG_TUD_ENDPOINT0_SIZE;
}
return tud_control_xfer(rhport, p_request, (void*) tud_descriptor_device_cb(), len);
}
break;
case TUSB_DESC_BOS:
@ -859,6 +875,7 @@ void dcd_event_handler(dcd_event_t const * event, bool in_isr)
{
case DCD_EVENT_UNPLUGGED:
_usbd_dev.connected = 0;
_usbd_dev.addressed = 0;
_usbd_dev.configured = 0;
_usbd_dev.suspended = 0;
osal_queue_send(_usbd_q, event, in_isr);

View File

@ -1,4 +1,4 @@
/*
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)

View File

@ -0,0 +1,626 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019-2020 William D. Jones
* Copyright (c) 2019-2020 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "tusb_option.h"
#if TUSB_OPT_DEVICE_ENABLED && ( CFG_TUSB_MCU == OPT_MCU_MSP430x5xx )
#include "msp430.h"
#include "device/dcd.h"
/*------------------------------------------------------------------*/
/* MACRO TYPEDEF CONSTANT ENUM
*------------------------------------------------------------------*/
// usbpllir_mirror and usbmaintl_mirror can be added later if needed.
static volatile uint16_t usbiepie_mirror = 0;
static volatile uint16_t usboepie_mirror = 0;
static volatile uint8_t usbie_mirror = 0;
static volatile uint16_t usbpwrctl_mirror = 0;
static bool in_isr = false;
uint8_t _setup_packet[8];
// Xfer control
typedef struct
{
uint8_t * buffer;
uint16_t total_len;
uint16_t queued_len;
uint16_t max_size;
bool short_packet;
} xfer_ctl_t;
xfer_ctl_t xfer_status[8][2];
#define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir]
// Accessing endpoint regs
typedef volatile uint8_t * ep_regs_t;
typedef enum
{
CNF = 0,
BBAX = 1,
BCTX = 2,
BBAY = 5,
BCTY = 6,
SIZXY = 7
} ep_regs_index_t;
#define EP_REGS(epnum, dir) &USBOEPCNF_1 + 64*dir + 8*(epnum - 1)
static void bus_reset(void)
{
// Hardcoded into the USB core.
xfer_status[0][TUSB_DIR_OUT].max_size = 8;
xfer_status[0][TUSB_DIR_IN].max_size = 8;
USBKEYPID = USBKEY;
// Enable the control EP 0. Also enable Indication Enable- a guard flag
// separate from the Interrupt Enable mask.
USBOEPCNF_0 |= (UBME | USBIIE);
USBIEPCNF_0 |= (UBME | USBIIE);
// Enable interrupts for this endpoint.
USBOEPIE |= BIT0;
USBIEPIE |= BIT0;
// Clear NAK until a setup packet is received.
USBOEPCNT_0 &= ~NAK;
USBIEPCNT_0 &= ~NAK;
USBCTL |= FEN; // Enable responding to packets.
// Dedicated buffers in hardware for SETUP and EP0, no setup needed.
// Now safe to respond to SETUP packets.
USBIE |= SETUPIE;
USBKEYPID = 0;
}
/*------------------------------------------------------------------*/
/* Controller API
*------------------------------------------------------------------*/
void dcd_init (uint8_t rhport)
{
(void) rhport;
USBKEYPID = USBKEY;
// Enable the module (required to write config regs)!
USBCNF |= USB_EN;
// Reset used interrupts
USBOEPIE = 0;
USBIEPIE = 0;
USBIE = 0;
USBOEPIFG = 0;
USBIEPIFG = 0;
USBIFG = 0;
USBPWRCTL &= ~(VUOVLIE | VBONIE | VBOFFIE | VUOVLIFG | VBONIFG | VBOFFIFG);
usboepie_mirror = 0;
usbiepie_mirror = 0;
usbie_mirror = 0;
usbpwrctl_mirror = 0;
USBVECINT = 0;
// Enable reset and wait for it before continuing.
USBIE |= RSTRIE;
// Enable pullup.
USBCNF |= PUR_EN;
USBKEYPID = 0;
}
// There is no "USB peripheral interrupt disable" bit on MSP430, so we have
// to save the relevant registers individually.
// WARNING: Unlike the ARM/NVIC routines, these functions are _not_ idempotent
// if you modified the registers saved in between calls so they don't match
// the mirrors; mirrors will be updated to reflect most recent register
// contents.
void dcd_int_enable (uint8_t rhport)
{
(void) rhport;
__bic_SR_register(GIE); // Unlikely to be called in ISR, but let's be safe.
// Also, this cleanly disables all USB interrupts
// atomically from application's POV.
// This guard is required because tinyusb can enable interrupts without
// having disabled them first.
if(in_isr)
{
USBOEPIE = usboepie_mirror;
USBIEPIE = usbiepie_mirror;
USBIE = usbie_mirror;
USBPWRCTL |= usbpwrctl_mirror;
}
in_isr = false;
__bis_SR_register(GIE);
}
void dcd_int_disable (uint8_t rhport)
{
(void) rhport;
__bic_SR_register(GIE);
usboepie_mirror = USBOEPIE;
usbiepie_mirror = USBIEPIE;
usbie_mirror = USBIE;
usbpwrctl_mirror = (USBPWRCTL & (VUOVLIE | VBONIE | VBOFFIE));
USBOEPIE = 0;
USBIEPIE = 0;
USBIE = 0;
USBPWRCTL &= ~(VUOVLIE | VBONIE | VBOFFIE);
in_isr = true;
__bis_SR_register(GIE);
}
void dcd_set_address (uint8_t rhport, uint8_t dev_addr)
{
(void) rhport;
USBFUNADR = dev_addr;
// Response with status after changing device address
dcd_edpt_xfer(rhport, tu_edpt_addr(0, TUSB_DIR_IN), NULL, 0);
}
void dcd_set_config (uint8_t rhport, uint8_t config_num)
{
(void) rhport;
(void) config_num;
// Nothing to do
}
void dcd_remote_wakeup(uint8_t rhport)
{
(void) rhport;
}
/*------------------------------------------------------------------*/
/* DCD Endpoint port
*------------------------------------------------------------------*/
bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt)
{
(void) rhport;
uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress);
uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress);
// Unsupported endpoint numbers/size or type (Iso not supported. Control
// not supported on nonzero endpoints).
if((desc_edpt->wMaxPacketSize.size > 64) || (epnum > 7) || \
(desc_edpt->bmAttributes.xfer == 0) || \
(desc_edpt->bmAttributes.xfer == 1)) {
return false;
}
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
xfer->max_size = desc_edpt->wMaxPacketSize.size;
// Buffer allocation scheme:
// For simplicity, only single buffer for now, since tinyusb currently waits
// for an xfer to complete before scheduling another one. This means only
// the X buffer is used.
//
// 1904 bytes are available, the max endpoint size supported on msp430 is
// 64 bytes. This is enough RAM for all 14 endpoints enabled _with_ double
// bufferring (64*14*2 = 1792 bytes). Extra RAM exists for triple and higher
// order bufferring, which must be maintained in software.
//
// For simplicity, each endpoint gets a hardcoded 64 byte chunk (regardless
// of actual wMaxPacketSize) whose start address is the following:
// addr = 128 * (epnum - 1) + 64 * dir.
//
// Double buffering equation:
// x_addr = 256 * (epnum - 1) + 128 * dir
// y_addr = x_addr + 64
// Address is right-shifted by 3 to fit into 8 bits.
uint8_t buf_base = (128 * (epnum - 1) + 64 * dir) >> 3;
// IN and OUT EP registers have the same structure.
ep_regs_t ep_regs = EP_REGS(epnum, dir);
// FIXME: I was able to get into a situation where OUT EP 3 would stall
// while debugging, despite stall code never being called. It appears
// these registers don't get cleared on reset, being part of RAM.
// Investigate and see if I can duplicate.
// Also, DBUF got set on OUT EP 2 while debugging. Only OUT EPs seem to be
// affected at this time. USB RAM directly precedes main RAM; perhaps I'm
// overwriting registers via buffer overflow w/ my debugging code?
ep_regs[SIZXY] = desc_edpt->wMaxPacketSize.size;
ep_regs[BCTX] |= NAK;
ep_regs[BBAX] = buf_base;
ep_regs[CNF] &= ~(TOGGLE | STALL | DBUF); // ISO xfers not supported on
// MSP430, so no need to gate DATA0/1 and frame
// behavior. Clear stall and double buffer bit as
// well- see above comment.
ep_regs[CNF] |= (UBME | USBIIE);
USBKEYPID = USBKEY;
if(dir == TUSB_DIR_OUT)
{
USBOEPIE |= (1 << epnum);
}
else
{
USBIEPIE |= (1 << epnum);
}
USBKEYPID = 0;
return true;
}
bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes)
{
(void) rhport;
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir);
xfer->buffer = buffer;
xfer->total_len = total_bytes;
xfer->queued_len = 0;
xfer->short_packet = false;
if(epnum == 0)
{
if(dir == TUSB_DIR_OUT)
{
// Interrupt will notify us when data was received.
USBCTL &= ~DIR;
USBOEPCNT_0 &= ~NAK;
}
else
{
// Kickstart the IN packet handler by queuing initial data and calling
// the ISR to transmit the first packet.
// Interrupt only fires on completed xfer.
USBCTL |= DIR;
USBIEPIFG |= BIT0;
}
}
else
{
ep_regs_t ep_regs = EP_REGS(epnum, dir);
if(dir == TUSB_DIR_OUT)
{
ep_regs[BCTX] &= ~NAK;
}
else
{
USBIEPIFG |= (1 << epnum);
}
}
return true;
}
void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr)
{
(void) rhport;
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
if(epnum == 0)
{
if(dir == TUSB_DIR_OUT)
{
USBOEPCNT_0 |= NAK;
USBOEPCNF_0 |= STALL;
}
else
{
USBIEPCNT_0 |= NAK;
USBIEPCNF_0 |= STALL;
}
}
else
{
ep_regs_t ep_regs = EP_REGS(epnum, dir);
ep_regs[CNF] |= STALL;
}
}
void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr)
{
(void) rhport;
uint8_t const epnum = tu_edpt_number(ep_addr);
uint8_t const dir = tu_edpt_dir(ep_addr);
if(epnum == 0)
{
if(dir == TUSB_DIR_OUT)
{
USBOEPCNF_0 &= ~STALL;
}
else
{
USBIEPCNF_0 &= ~STALL;
}
}
else
{
ep_regs_t ep_regs = EP_REGS(epnum, dir);
// Required by USB spec to reset DATA toggle bit to DATA0 on interrupt
// and bulk endpoints.
ep_regs[CNF] &= ~(STALL + TOGGLE);
}
}
void dcd_edpt0_status_complete(uint8_t rhport, tusb_control_request_t const * request)
{
(void) rhport;
(void) request;
// FIXME: Per manual, we should be clearing the NAK bits of EP0 after the
// Status Phase of a control xfer is done, in preparation of another possible
// SETUP packet. However, from my own testing, SETUP packets _are_ correctly
// handled by the USB core without clearing the NAKs.
//
// Right now, clearing NAKs in this callbacks causes a direction mismatch
// between host and device on EP0. Figure out why and come back to this.
// USBOEPCNT_0 &= ~NAK;
// USBIEPCNT_0 &= ~NAK;
}
/*------------------------------------------------------------------*/
static void receive_packet(uint8_t ep_num)
{
xfer_ctl_t * xfer = XFER_CTL_BASE(ep_num, TUSB_DIR_OUT);
ep_regs_t ep_regs = EP_REGS(ep_num, TUSB_DIR_OUT);
uint8_t xfer_size;
if(ep_num == 0)
{
xfer_size = USBOEPCNT_0 & 0x0F;
}
else
{
xfer_size = ep_regs[BCTX] & 0x7F;
}
uint16_t remaining = xfer->total_len - xfer->queued_len;
uint16_t to_recv_size;
if(remaining <= xfer->max_size) {
// Avoid buffer overflow.
to_recv_size = (xfer_size > remaining) ? remaining : xfer_size;
} else {
// Room for full packet, choose recv_size based on what the microcontroller
// claims.
to_recv_size = (xfer_size > xfer->max_size) ? xfer->max_size : xfer_size;
}
uint8_t * base = (xfer->buffer + xfer->queued_len);
if(ep_num == 0)
{
volatile uint8_t * ep0out_buf = &USBOEP0BUF;
for(uint16_t i = 0; i < to_recv_size; i++)
{
base[i] = ep0out_buf[i];
}
}
else
{
volatile uint8_t * ep_buf = &USBSTABUFF + (ep_regs[BBAX] << 3);
for(uint16_t i = 0; i < to_recv_size ; i++)
{
base[i] = ep_buf[i];
}
}
xfer->queued_len += xfer_size;
xfer->short_packet = (xfer_size < xfer->max_size);
if((xfer->total_len == xfer->queued_len) || xfer->short_packet)
{
dcd_event_xfer_complete(0, ep_num, xfer->queued_len, XFER_RESULT_SUCCESS, true);
}
else
{
// Schedule to receive another packet.
if(ep_num == 0)
{
USBOEPCNT_0 &= ~NAK;
}
else
{
ep_regs[BCTX] &= ~NAK;
}
}
}
static void transmit_packet(uint8_t ep_num)
{
xfer_ctl_t * xfer = XFER_CTL_BASE(ep_num, TUSB_DIR_IN);
// First, determine whether we should even send a packet or finish
// up the xfer.
bool zlp = (xfer->total_len == 0); // By necessity, xfer->total_len will
// equal xfer->queued_len for ZLPs.
// Of course a ZLP is a short packet.
if((!zlp && (xfer->total_len == xfer->queued_len)) || xfer->short_packet)
{
dcd_event_xfer_complete(0, ep_num | TUSB_DIR_IN_MASK, xfer->queued_len, XFER_RESULT_SUCCESS, true);
return;
}
// Then actually commit to transmit a packet.
uint8_t * base = (xfer->buffer + xfer->queued_len);
uint16_t remaining = xfer->total_len - xfer->queued_len;
uint8_t xfer_size = (xfer->max_size < xfer->total_len) ? xfer->max_size : remaining;
xfer->queued_len += xfer_size;
if(xfer_size < xfer->max_size)
{
// Next "xfer complete interrupt", the transfer will end.
xfer->short_packet = true;
}
if(ep_num == 0)
{
volatile uint8_t * ep0in_buf = &USBIEP0BUF;
for(uint16_t i = 0; i < xfer_size; i++)
{
ep0in_buf[i] = base[i];
}
USBIEPCNT_0 = (USBIEPCNT_0 & 0xF0) + xfer_size;
USBIEPCNT_0 &= ~NAK;
}
else
{
ep_regs_t ep_regs = EP_REGS(ep_num, TUSB_DIR_IN);
volatile uint8_t * ep_buf = &USBSTABUFF + (ep_regs[BBAX] << 3);
for(int i = 0; i < xfer_size; i++)
{
ep_buf[i] = base[i];
}
ep_regs[BCTX] = (ep_regs[BCTX] & 0x80) + (xfer_size & 0x7F);
ep_regs[BCTX] &= ~NAK;
}
}
static void handle_setup_packet(void)
{
volatile uint8_t * setup_buf = &USBSUBLK;
for(int i = 0; i < 8; i++)
{
_setup_packet[i] = setup_buf[i];
}
// Clearing SETUPIFG by reading USBVECINT does not set NAK, so now that we
// have a SETUP packet, force NAKs until tinyusb can handle the SETUP
// packet and prepare for a new xfer.
USBIEPCNT_0 |= NAK;
USBOEPCNT_0 |= NAK;
dcd_event_setup_received(0, (uint8_t*) &_setup_packet[0], true);
}
void __attribute__ ((interrupt(USB_UBM_VECTOR))) USB_UBM_ISR(void)
{
// Setup is special- reading USBVECINT to handle setup packets is done to
// stop hardware-generated NAKs on EP0.
uint8_t setup_status = USBIFG & SETUPIFG;
if(setup_status)
{
handle_setup_packet();
}
uint16_t curr_vector = USBVECINT;
switch(curr_vector)
{
case USBVECINT_RSTR:
bus_reset();
dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true);
break;
// Clear the (hardware-enforced) NAK on EP 0 after a SETUP packet
// is received. At this point, even though the hardware is no longer
// forcing NAKs, the EP0 NAK bits should still be set to avoid
// sending/receiving data before tinyusb is ready.
//
// Furthermore, it's possible for the hardware to STALL in the middle of
// a control xfer if the EP0 NAK bits aren't set properly.
// See: https://e2e.ti.com/support/microcontrollers/msp430/f/166/t/845259
// From my testing, if all of the following hold:
// * OUT EP0 NAK is cleared.
// * IN EP0 NAK is set.
// * DIR bit in USBCTL is clear.
// and an IN packet is received on EP0, the USB core will STALL. Setting
// both EP0 NAKs manually when a SETUP packet is received, as is done
// in handle_setup_packet(), avoids meeting STALL conditions.
//
// TODO: Figure out/explain why the STALL condition can be reached in the
// first place. When I first noticed the STALL, the only two places I
// touched the NAK bits were in dcd_edpt_xfer() and to _set_ (sic) them in
// bus_reset(). SETUP packet handling should've been unaffected.
case USBVECINT_SETUP_PACKET_RECEIVED:
break;
case USBVECINT_INPUT_ENDPOINT0:
transmit_packet(0);
break;
case USBVECINT_OUTPUT_ENDPOINT0:
receive_packet(0);
break;
case USBVECINT_INPUT_ENDPOINT1:
case USBVECINT_INPUT_ENDPOINT2:
case USBVECINT_INPUT_ENDPOINT3:
case USBVECINT_INPUT_ENDPOINT4:
case USBVECINT_INPUT_ENDPOINT5:
case USBVECINT_INPUT_ENDPOINT6:
case USBVECINT_INPUT_ENDPOINT7:
{
uint8_t ep = ((curr_vector - USBVECINT_INPUT_ENDPOINT1) >> 1) + 1;
transmit_packet(ep);
}
break;
case USBVECINT_OUTPUT_ENDPOINT1:
case USBVECINT_OUTPUT_ENDPOINT2:
case USBVECINT_OUTPUT_ENDPOINT3:
case USBVECINT_OUTPUT_ENDPOINT4:
case USBVECINT_OUTPUT_ENDPOINT5:
case USBVECINT_OUTPUT_ENDPOINT6:
case USBVECINT_OUTPUT_ENDPOINT7:
{
uint8_t ep = ((curr_vector - USBVECINT_OUTPUT_ENDPOINT1) >> 1) + 1;
receive_packet(ep);
}
break;
default:
while(true);
break;
}
}
#endif

View File

@ -71,7 +71,7 @@ char const* const tusb_strerr[TUSB_ERROR_COUNT] = { ERROR_TABLE(ERROR_STRING) };
static void dump_str_line(uint8_t const* buf, uint16_t count)
{
// each line is 16 bytes
for(int i=0; i<count; i++)
for(uint16_t i=0; i<count; i++)
{
const char ch = buf[i];
tu_printf("%c", isprint(ch) ? ch : '.');
@ -131,7 +131,7 @@ void tu_print_mem(void const *buf, uint16_t count, uint8_t indent)
if ( remain )
{
for(int i=0; i< 16-remain; i++)
for(uint16_t i=0; i< 16-remain; i++)
{
tu_printf(" ");
for(int j=0; j<2*size; j++) tu_printf(" ");

View File

@ -71,8 +71,12 @@
#define OPT_MCU_STM32L1 308 ///< ST STM32L1
#define OPT_MCU_STM32L4 309 ///< ST STM32L4
// Sony
#define OPT_MCU_CXD56 400 ///< SONY CXD56
// TI MSP430
#define OPT_MCU_MSP430x5xx 500 ///< TI MSP430x5xx
#define OPT_MCU_VALENTYUSB_EPTRI 600 ///< Fomu eptri config
#define OPT_MCU_MIMXRT10XX 700 ///< NXP iMX RT10xx