Add USB CDC and loop-back test

This commit is contained in:
fruchti 2020-10-11 22:37:46 +02:00
commit 7234eb8360
34 changed files with 15808 additions and 0 deletions

View file

@ -0,0 +1,8 @@
#pragma once
extern char __BUILD_DATE;
extern char __BUILD_NUMBER;
#define BUILD_DATE ((uint32_t)&__BUILD_DATE)
#define BUILD_NUMBER ((uint32_t)&__BUILD_NUMBER)

View file

@ -0,0 +1,4 @@
#pragma once
#define CONFIG_USB_RINGBUFFER_SIZE \
256

24
stm32f103c8t6/src/debug.c Normal file
View file

@ -0,0 +1,24 @@
#include "debug.h"
void Debug_Print(const char *message)
{
uint32_t m[] = {2, (uint32_t)message, strlen(message)};
__asm__("mov r0, #0x05;"
"mov r1, %[m];"
"bkpt #0xAB"
:
: [m] "r" (m)
: "r0", "r1", "memory");
}
void Debug_PutChar(char c)
{
uint32_t m[] = {2, (uint32_t)(&c), 1};
__asm__("mov r0, #0x05;"
"mov r1, %[m];"
"bkpt #0xAB"
:
: [m] "r" (m)
: "r0", "r1", "memory");
}

10
stm32f103c8t6/src/debug.h Normal file
View file

@ -0,0 +1,10 @@
#pragma once
#include <stdint.h>
#include <string.h>
#include "stm32f103x6.h"
void Debug_Print(const char *message);
void Debug_PutChar(char c);

15
stm32f103c8t6/src/led.c Normal file
View file

@ -0,0 +1,15 @@
#include "led.h"
#include "ownership.h"
MODULE_OWNS_PIN(GPIOB, PIN_LED);
void LED_Init(void)
{
RCC->APB2ENR |= RCC_APB2ENR_IOPCEN;
GPIOC->CRH = (GPIOB->CRH
& ~(0x0f << (PIN_LED * 4 - 32)))
| (0x02 << (PIN_LED * 4 - 32)) // 2 MHz push-pull output
;
}

10
stm32f103c8t6/src/led.h Normal file
View file

@ -0,0 +1,10 @@
#pragma once
#include "stm32f103x6.h"
#include "pinning.h"
#define LED_ON() do { GPIOC->BRR = 1 << PIN_LED; } while(0);
#define LED_OFF() do { GPIOC->BSRR = 1 << PIN_LED; } while(0);
void LED_Init(void);

50
stm32f103c8t6/src/main.c Normal file
View file

@ -0,0 +1,50 @@
#include "main.h"
static void Clock_Init(void)
{
// Activate HSE and wait for it to be ready
RCC->CR = RCC_CR_HSEON;
while(!(RCC->CR & RCC_CR_HSERDY));
RCC->CFGR = RCC_CFGR_SW_0;
while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_0);
FLASH->ACR |= FLASH_ACR_LATENCY_1;
// Set PLL to x9 (-> 72MHz system clock)
RCC->CFGR |= RCC_CFGR_PLLMULL9 | RCC_CFGR_PLLSRC | RCC_CFGR_PPRE1_2;
// Activate PLL and wait
RCC->CR |= RCC_CR_PLLON;
while(!(RCC->CR & RCC_CR_PLLRDY));
// Select PLL as clock source
RCC->CFGR = (RCC->CFGR & ~RCC_CFGR_SW) | RCC_CFGR_SW_1;
// Resulting clocks:
// SYSCLK, AHB, APB2 72 Mhz
// APB1, ADC 36 MHz
// Disable all interrupts
RCC->CIR = 0x00000000;
}
int main(void)
{
Clock_Init();
LED_Init();
USB_Init();
LED_ON();
uint8_t buffer[32];
for(;;)
{
int length = USBCDC_ReceiveData(buffer, sizeof(buffer));
if(length)
{
USBCDC_SendData(buffer, length);
}
// __WFI();
}
}

12
stm32f103c8t6/src/main.h Normal file
View file

@ -0,0 +1,12 @@
#pragma once
#include <stdbool.h>
#include "stm32f103x6.h"
#include "pinning.h"
#include "buildid.h"
#include "debug.h"
#include "usb.h"
#include "led.h"
#include "usb_cdc.h"
int main(void);

View file

@ -0,0 +1,13 @@
#pragma once
#define _PASTE(x, y) x ## y
#define PASTE(x, y) _PASTE(x, y)
#define MODULE_OWNS_PERIPHERAL(peripheral) \
void *_PERIPHERAL_OWNERSHIP_ ## peripheral \
= (void*)(peripheral)
#define MODULE_OWNS_PIN(gpio, pin) \
void *PASTE(_PIN_OWNERSHIP_ ## gpio ## _, pin) \
= (void*)(gpio + pin)

View file

@ -0,0 +1,10 @@
#pragma once
// Port A
#define PIN_USB_DM 11 // PA11 - USB_DM
#define PIN_USB_DP 12 // PA12 - USB_DP
// #define PIN_USB_PULLUP 15 // PA15 - 1.5 kΩ to D+
// Port C
#define PIN_LED 13 // PC13 - Status LED

244
stm32f103c8t6/src/startup.S Normal file
View file

@ -0,0 +1,244 @@
.syntax unified
.thumb
.fpu softvfp
.global Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
init_data:
ldr r2, =_start_init_data
ldr r3, =_start_data
ldr r1, =_end_data
init_data_loop:
cmp r3, r1
bhs zero_bss
ldr r0, [r2], #4
str r0, [r3], #4
b init_data_loop
zero_bss:
ldr r3, =_start_bss
ldr r1, =_end_bss
movs r0, #0
zero_bss_loop:
cmp r3, r1
bhs init_finished
str r0, [r3], #4
b zero_bss_loop
init_finished:
// bl __libc_init_array // Uncomment if static constructors are needed
bl main
infinite_loop:
b infinite_loop
.size Reset_Handler, .-Reset_Handler
.section .cortex_vectors, "a"
.word _end_stack
.word Reset_Handler
.word NMI_Handler
.word HardFault_Handler
.word MemManage_Handler
.word BusFault_Handler
.word UsageFault_Handler
.word 0x00000000
.word 0x00000000
.word 0x00000000
.word 0x00000000
.word SVC_Handler
.word DebugMon_Handler
.word 0x00000000
.word PendSV_Handler
.word SysTick_Handler
.word WWDG_IRQHandler
.word PVD_IRQHandler
.word TAMPER_IRQHandler
.word RTC_IRQHandler
.word FLASH_IRQHandler
.word RCC_IRQHandler
.word EXTI0_IRQHandler
.word EXTI1_IRQHandler
.word EXTI2_IRQHandler
.word EXTI3_IRQHandler
.word EXTI4_IRQHandler
.word DMA1_Channel1_IRQHandler
.word DMA1_Channel2_IRQHandler
.word DMA1_Channel3_IRQHandler
.word DMA1_Channel4_IRQHandler
.word DMA1_Channel5_IRQHandler
.word DMA1_Channel6_IRQHandler
.word DMA1_Channel7_IRQHandler
.word ADC1_2_IRQHandler
.word USB_HP_CAN1_TX_IRQHandler
.word USB_LP_CAN1_RX0_IRQHandler
.word CAN1_RX1_IRQHandler
.word CAN1_SCE_IRQHandler
.word EXTI9_5_IRQHandler
.word TIM1_BRK_IRQHandler
.word TIM1_UP_IRQHandler
.word TIM1_TRG_COM_IRQHandler
.word TIM1_CC_IRQHandler
.word TIM2_IRQHandler
.word TIM3_IRQHandler
.word 0x00000000
.word I2C1_EV_IRQHandler
.word I2C1_ER_IRQHandler
.word 0x00000000
.word 0x00000000
.word SPI1_IRQHandler
.word 0x00000000
.word USART1_IRQHandler
.word USART2_IRQHandler
.word 0x00000000
.word EXTI15_10_IRQHandler
.word RTC_Alarm_IRQHandler
.word USBWakeUp_IRQHandler
.type Dummy_Handler, %function
Dummy_Handler:
b Dummy_Handler
.weak NMI_Handler
.thumb_set NMI_Handler, Dummy_Handler
.weak HardFault_Handler
.thumb_set HardFault_Handler, Dummy_Handler
.weak MemManage_Handler
.thumb_set MemManage_Handler, Dummy_Handler
.weak BusFault_Handler
.thumb_set BusFault_Handler, Dummy_Handler
.weak UsageFault_Handler
.thumb_set UsageFault_Handler, Dummy_Handler
.weak SVC_Handler
.thumb_set SVC_Handler, Dummy_Handler
.weak DebugMon_Handler
.thumb_set DebugMon_Handler, Dummy_Handler
.weak PendSV_Handler
.thumb_set PendSV_Handler, Dummy_Handler
.weak SysTick_Handler
.thumb_set SysTick_Handler, Dummy_Handler
.weak WWDG_IRQHandler
.thumb_set WWDG_IRQHandler, Dummy_Handler
.weak PVD_IRQHandler
.thumb_set PVD_IRQHandler, Dummy_Handler
.weak TAMPER_IRQHandler
.thumb_set TAMPER_IRQHandler, Dummy_Handler
.weak RTC_IRQHandler
.thumb_set RTC_IRQHandler, Dummy_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler, Dummy_Handler
.weak RCC_IRQHandler
.thumb_set RCC_IRQHandler, Dummy_Handler
.weak EXTI0_IRQHandler
.thumb_set EXTI0_IRQHandler, Dummy_Handler
.weak EXTI1_IRQHandler
.thumb_set EXTI1_IRQHandler, Dummy_Handler
.weak EXTI2_IRQHandler
.thumb_set EXTI2_IRQHandler, Dummy_Handler
.weak EXTI3_IRQHandler
.thumb_set EXTI3_IRQHandler, Dummy_Handler
.weak EXTI4_IRQHandler
.thumb_set EXTI4_IRQHandler, Dummy_Handler
.weak DMA1_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler, Dummy_Handler
.weak DMA1_Channel2_IRQHandler
.thumb_set DMA1_Channel2_IRQHandler, Dummy_Handler
.weak DMA1_Channel3_IRQHandler
.thumb_set DMA1_Channel3_IRQHandler, Dummy_Handler
.weak DMA1_Channel4_IRQHandler
.thumb_set DMA1_Channel4_IRQHandler, Dummy_Handler
.weak DMA1_Channel5_IRQHandler
.thumb_set DMA1_Channel5_IRQHandler, Dummy_Handler
.weak DMA1_Channel6_IRQHandler
.thumb_set DMA1_Channel6_IRQHandler, Dummy_Handler
.weak DMA1_Channel7_IRQHandler
.thumb_set DMA1_Channel7_IRQHandler, Dummy_Handler
.weak ADC1_2_IRQHandler
.thumb_set ADC1_2_IRQHandler, Dummy_Handler
.weak USB_HP_CAN1_TX_IRQHandler
.thumb_set USB_HP_CAN1_TX_IRQHandler, Dummy_Handler
.weak USB_LP_CAN1_RX0_IRQHandler
.thumb_set USB_LP_CAN1_RX0_IRQHandler, Dummy_Handler
.weak CAN1_RX1_IRQHandler
.thumb_set CAN1_RX1_IRQHandler, Dummy_Handler
.weak CAN1_SCE_IRQHandler
.thumb_set CAN1_SCE_IRQHandler, Dummy_Handler
.weak EXTI9_5_IRQHandler
.thumb_set EXTI9_5_IRQHandler, Dummy_Handler
.weak TIM1_BRK_IRQHandler
.thumb_set TIM1_BRK_IRQHandler, Dummy_Handler
.weak TIM1_UP_IRQHandler
.thumb_set TIM1_UP_IRQHandler, Dummy_Handler
.weak TIM1_TRG_COM_IRQHandler
.thumb_set TIM1_TRG_COM_IRQHandler, Dummy_Handler
.weak TIM1_CC_IRQHandler
.thumb_set TIM1_CC_IRQHandler, Dummy_Handler
.weak TIM2_IRQHandler
.thumb_set TIM2_IRQHandler, Dummy_Handler
.weak TIM3_IRQHandler
.thumb_set TIM3_IRQHandler, Dummy_Handler
.weak I2C1_EV_IRQHandler
.thumb_set I2C1_EV_IRQHandler, Dummy_Handler
.weak I2C1_ER_IRQHandler
.thumb_set I2C1_ER_IRQHandler, Dummy_Handler
.weak SPI1_IRQHandler
.thumb_set SPI1_IRQHandler, Dummy_Handler
.weak USART1_IRQHandler
.thumb_set USART1_IRQHandler, Dummy_Handler
.weak USART2_IRQHandler
.thumb_set USART2_IRQHandler, Dummy_Handler
.weak EXTI15_10_IRQHandler
.thumb_set EXTI15_10_IRQHandler, Dummy_Handler
.weak RTC_Alarm_IRQHandler
.thumb_set RTC_Alarm_IRQHandler, Dummy_Handler
.weak USBWakeUp_IRQHandler
.thumb_set USBWakeUp_IRQHandler, Dummy_Handler

276
stm32f103c8t6/src/usb.c Normal file
View file

@ -0,0 +1,276 @@
#include "usb.h"
#include "usb_descriptors.h"
#include "usb_util.h"
#include "usb_cdc.h"
#include "usb_vendor.h"
#include "led.h"
#include "ownership.h"
MODULE_OWNS_PERIPHERAL(USB);
MODULE_OWNS_PIN(GPIOA, PIN_USB_DM);
MODULE_OWNS_PIN(GPIOA, PIN_USB_DP);
USB_PacketHandler_t USB_EP0OutPacketHandler;
uint8_t USB_DeviceStatus[2] = {0x00, 0x01};
volatile unsigned int USB_ResetCount = 0;
volatile unsigned int USB_Address = 0;
void USB_Init(void)
{
// GPIOA clock
RCC->APB2ENR |= RCC_APB2ENR_IOPAEN;
RCC->APB2ENR |= RCC_APB2ENR_AFIOEN;
RCC->APB1ENR |= RCC_APB1ENR_USBEN;
GPIOA->CRH &= ~(GPIO_CRH_CNF11 | GPIO_CRH_MODE11
| GPIO_CRH_CNF12 | GPIO_CRH_MODE12);
GPIOA->CRH |= GPIO_CRH_MODE11 | GPIO_CRH_MODE12;
GPIOA->ODR &= ~(GPIO_CRH_MODE11 | GPIO_CRH_MODE12);
USB_Delay(100000);
// Enable reset and correct transfer interrupts
NVIC_EnableIRQ(USB_LP_IRQn);
NVIC_SetPriority(USB_LP_IRQn, 7);
// Analog power up
USB->CNTR = (uint16_t)USB_CNTR_FRES;
// Minimum delay: 1 µs
USB_Delay(3000);
USB->CNTR = (uint16_t)0;
USB->ISTR = (uint16_t)0;
USB->CNTR = (uint16_t)(USB_CNTR_RESETM | USB_CNTR_CTRM);
// Configure USB pins (PA11 and PA12 in AF mode, 50 MHz push-pull)
GPIOA->CRH |= GPIO_CRH_CNF11_1 | GPIO_CRH_MODE11 |\
GPIO_CRH_CNF12_1 | GPIO_CRH_MODE12;
}
static inline void USB_HandleReset(void)
{
// Remove reset flag
USB->ISTR = (uint16_t)~(USB_ISTR_RESET);
USB_ResetCount++;
// Set buffer table origin
USB->BTABLE = USB_BTABLE_OFFSET;
// Set buffer table contents for control endpoint 0
USB_BTABLE_ENTRIES[0].COUNT_RX = USB_EP_RXCOUNT_BL_SIZE | (1 << 10);
USB_BTABLE_ENTRIES[0].ADDR_RX = 0x40;
USB_BTABLE_ENTRIES[0].COUNT_TX = 0;
USB_BTABLE_ENTRIES[0].ADDR_TX = 0x80;
// Configure endpoint 0
USB_SetEPR(&(USB->EP0R), USB_EPR_EP_TYPE_CONTROL
| USB_EPR_STAT_TX_NAK | USB_EPR_STAT_RX_VALID);
USBCDC_InitEndpoints();
// Enable
USB->DADDR = USB_DADDR_EF;
LED_OFF();
}
static inline void USB_HandleIn(void)
{
if((USB->DADDR & USB_DADDR_ADD) != USB_Address)
{
USB->DADDR = USB_Address | USB_DADDR_EF;
}
// Ready for next packet
USB_SetEPRXStatus(&USB->EP0R, USB_EP_RX_VALID);
}
static inline void USB_Handle0Out(void)
{
int length = USB_BTABLE_ENTRIES[0].COUNT_RX & 0x3ff;
if(length != 0)
{
if(USB_EP0OutPacketHandler != NULL)
{
USB_EP0OutPacketHandler(length);
}
}
// Ready for next packet
USB_SetEPRXStatus(&USB->EP0R, USB_EP_RX_VALID);
}
static inline void USB_HandleSetup(void)
{
USB_SetupPacket_t sp;
USB_PMAToMemory((uint8_t*)&sp, USB_BTABLE_ENTRIES[0].ADDR_RX,
sizeof(USB_SetupPacket_t));
// Delete this: Sanity check for abnormal setup package lengths
unsigned int packet_length = USB_BTABLE_ENTRIES[0].COUNT_RX & 0x3ff;
if(packet_length > sizeof(USB_SetupPacket_t))
{
__asm__ volatile("bkpt");
}
const void *reply_data = NULL;
int reply_length = 0;
uint8_t reply_response = USB_TOKEN_ACK;
if((sp.bmRequestType & (USB_REQUEST_TYPE | USB_REQUEST_RECIPIENT))
== (USB_REQUEST_TYPE_STANDARD | USB_REQUEST_RECIPIENT_DEVICE))
{
switch(sp.bRequest)
{
case USB_REQUEST_GET_STATUS:;
if(sp.wValue == 0 && sp.wIndex == 0 && sp.wLength == 2)
{
reply_length = 2;
reply_data = USB_DeviceStatus;
}
break;
case USB_REQUEST_GET_DESCRIPTOR:;
USB_DescriptorType_t descriptor_type = sp.wValue >> 8;
int descriptor_index = sp.wValue & 0xff;
reply_length = sp.wLength;
USB_HandleGetDescriptor(descriptor_type, descriptor_index,
&reply_data, &reply_length, &reply_response);
break;
case USB_REQUEST_SET_ADDRESS:
USB_Address = sp.wValue & USB_DADDR_ADD;
reply_response = USB_EP_TX_VALID;
break;
case USB_REQUEST_SET_CONFIGURATION:
reply_response = USB_EP_TX_VALID;
break;
default:;
__asm__ volatile("nop");
reply_response = USB_EP_TX_STALL;
break;
}
}
else if((sp.bmRequestType & (USB_REQUEST_TYPE | USB_REQUEST_RECIPIENT))
== (USB_REQUEST_TYPE_CLASS | USB_REQUEST_RECIPIENT_INTERFACE))
{
USBCDC_HandleInterfaceSetup(&sp, &reply_data, &reply_length,
&reply_response);
}
else if((sp.bmRequestType & (USB_REQUEST_TYPE | USB_REQUEST_RECIPIENT))
== (USB_REQUEST_TYPE_VENDOR | USB_REQUEST_RECIPIENT_DEVICE))
{
USBVendor_HandleDeviceSetup(&sp, &reply_data, &reply_length,
&reply_response);
}
else
{
// Unknown request
__asm__ volatile("bkpt");
}
if(reply_data)
{
// Reply with data
USB_MemoryToPMA(USB_BTABLE_ENTRIES[0].ADDR_TX, reply_data,
reply_length);
USB_BTABLE_ENTRIES[0].COUNT_TX = reply_length;
USB_SetEPTXStatus(&(USB->EP0R), USB_EP_TX_VALID);
}
else
{
// Send response
USB_BTABLE_ENTRIES[0].COUNT_TX = 0;
USB_SetEPTXStatus(&(USB->EP0R), reply_response);
}
// Ready for the next packet
USB_SetEPRXStatus(&(USB->EP0R), USB_EP_RX_VALID);
}
// Interrupt service routine
void USB_LP_IRQHandler(void)
{
if(USB->ISTR & USB_ISTR_RESET)
{
// Reset happened
USB_HandleReset();
return;
}
uint16_t istr;
while((istr = USB->ISTR) & (USB_ISTR_CTR))
{
if(istr & USB_ISTR_CTR)
{
// Correct transfer
int ep = istr & USB_ISTR_EP_ID;
switch(ep)
{
case 0:
// Determine transfer direction
if(istr & USB_ISTR_DIR)
{
// Out transfer
if(USB->EP0R & USB_EP0R_SETUP)
{
// Clear CTR_RX
USB->EP0R = USB->EP0R & (USB_EP0R_SETUP
| USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND
| USB_EP0R_CTR_TX | USB_EP0R_EA);
// Setup packed received
USB_HandleSetup();
}
else
{
// Clear CTR_RX
USB->EP0R = USB->EP0R & (USB_EP0R_SETUP
| USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND
| USB_EP0R_CTR_TX | USB_EP0R_EA);
USB_Handle0Out();
}
}
else
{
// In transfer
// Clear CTR_TX
USB->EP0R = USB->EP0R & (USB_EP0R_CTR_RX
| USB_EP0R_SETUP | USB_EP0R_EP_TYPE
| USB_EP0R_EP_KIND | USB_EP0R_EA);
// In transfer
USB_HandleIn();
}
break;
case 2:
// Data in transfer finished.
USB_BTABLE_ENTRIES[2].COUNT_TX = 0;
USB_ClearEPCTTX(&USB->EP2R);
// Start the next in transfer, if there is data left in the
// buffer
USBCDC_HandleDataInComplete();
break;
case 3:
// A successful out transfer on endpoint 3 means new data
// arrived on the virtual serial port
USBCDC_HandleDataOut();
USB_ClearEPCTRX(&USB->EP3R);
break;
default:
// Other endpoints are not implemented (most importantly the
// notification interrupt endpoint 1)
__asm__ volatile("bkpt");
break;
}
}
}
}

136
stm32f103c8t6/src/usb.h Normal file
View file

@ -0,0 +1,136 @@
#pragma once
#include <string.h>
#include <stdbool.h>
#include "stm32f103x6.h"
#include "pinning.h"
#include "debug.h"
#define USB_TOKEN_OUT 0b0001
#define USB_TOKEN_IN 0x1001
#define USB_TOKEN_SOF 0b0101
#define USB_TOKEN_SETUP 0b1101
#define USB_TOKEN_DATA0 0b0011
#define USB_TOKEN_DATA1 0b1011
#define USB_TOKEN_DATA2 0b0111
#define USB_TOKEN_ACK 0b0010
#define USB_TOKEN_NAK 0b1010
#define USB_TOKEN_STALL 0b1110
#define USB_TOKEN_NYET 0b0110
#define USB_TOKEN_PRE 0b1100
#define USB_TOKEN_ERR 0b1100
#define USB_TOKEN_SPLIT 0b1000
#define USB_TOKEN_PING 0b0100
#define USB_REQUEST_DIRECTION (1 << 7)
#define USB_REQUEST_DIRECTION_OUT 0
#define USB_REQUEST_DIRECTION_IN (1 << 7)
#define USB_REQUEST_TYPE (0x3 << 5)
#define USB_REQUEST_TYPE_STANDARD 0
#define USB_REQUEST_TYPE_CLASS (1 << 5)
#define USB_REQUEST_TYPE_VENDOR (2 << 5)
#define USB_REQUEST_TYPE_RESERVED (3 << 5)
#define USB_REQUEST_RECIPIENT 0x1f
#define USB_REQUEST_RECIPIENT_DEVICE 0
#define USB_REQUEST_RECIPIENT_INTERFACE 1
#define USB_REQUEST_RECIPIENT_ENDPOINT 2
#define USB_REQUEST_RECIPIENT_OTHER 3
#define USB_REQUEST_CLEAR_FEATURE 1
// wValue = <feature>, wIndex = 0|<interface>|<endpoint>, wLength = 0
#define USB_REQUEST_GET_CONFIGURATION 8
// wValue = 0, wIndex = 0, wLength = 1
#define USB_REQUEST_GET_DESCRIPTOR 6
// wValue = <descriptor type>:<descriptor index>, wIndex = 0|<language>,
// wLength = <descriptor length>
#define USB_REQUEST_GET_INTERFACE 10
// wValue = 0, wIndex = <interface>, wLength = 1
#define USB_REQUEST_GET_STATUS 0
// wValue = 0, wIndex = 0|<interface>|<endpoint>, wLength = 2
#define USB_REQUEST_SET_ADDRESS 5
// wValue = <address>, wIndex = 0, wLength = 0
#define USB_REQUEST_SET_CONFIGURATION 9
// wValue = <configuration value>, wIndex = 0, wLength = 0
#define USB_REQUEST_SET_DESCRIPTOR 7
// wValue = <descriptor type>:<descriptor index>, wIndex = 0|<language>,
// wLength = <descriptor length>
#define USB_REQUEST_SET_FEATURE 3
// wValue = <feature selector>, wIndex = 0|<interface>|<endpoint>,
// wLength = 0
#define USB_REQUEST_SET_INTERFACE 11
// wValue = <alternate setting>, wIndex = <interface>, wLength = 0
#define USB_REQUEST_SYNCH_FRAME 12
// wValue = 0, wIndex = <endpoint>, wLength = 2
#define USB_EPR_STAT_TX_DISABLED 0x00
#define USB_EPR_STAT_TX_STALL USB_EP0R_STAT_TX_0
#define USB_EPR_STAT_TX_NAK USB_EP0R_STAT_TX_1
#define USB_EPR_STAT_TX_VALID (USB_EP0R_STAT_TX_0 \
| USB_EP0R_STAT_TX_1)
#define USB_EPR_STAT_RX_DISABLED 0x00
#define USB_EPR_STAT_RX_STALL USB_EP0R_STAT_RX_0
#define USB_EPR_STAT_RX_NAK USB_EP0R_STAT_RX_1
#define USB_EPR_STAT_RX_VALID (USB_EP0R_STAT_RX_0 \
| USB_EP0R_STAT_RX_1)
#define USB_EPR_EP_TYPE_BULK 0x00
#define USB_EPR_EP_TYPE_CONTROL USB_EP0R_EP_TYPE_0
#define USB_EPR_EP_TYPE_ISO USB_EP0R_EP_TYPE_1
#define USB_EPR_EP_TYPE_INTERRUPT (USB_EP0R_EP_TYPE_0 \
| USB_EP0R_EP_TYPE_1)
#define USB_PMA_ADDR 0x40006000UL
#define USB_BTABLE_OFFSET 0x00
#define USB_EP_RXCOUNT_BL_SIZE (1 << 15)
typedef struct
{
volatile union
{
volatile uint16_t ADDR_TX;
volatile uint16_t ADDR_RX_0;
volatile uint16_t ADDR_TX_0;
};
volatile uint16_t rsvd1;
volatile union
{
volatile uint16_t COUNT_TX;
volatile uint16_t COUNT_RX_0;
volatile uint16_t COUNT_TX_0;
};
volatile uint16_t rsvd2;
volatile union
{
volatile uint16_t ADDR_RX;
volatile uint16_t ADDR_RX_1;
volatile uint16_t ADDR_TX_1;
};
volatile uint16_t rsvd3;
volatile union
{
volatile uint16_t COUNT_RX;
volatile uint16_t COUNT_RX_1;
volatile uint16_t COUNT_TX_1;
};
volatile uint16_t rsvd4;
} __attribute__((packed, aligned(4))) USB_BufferTableEntry_t;
typedef struct
{
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} __attribute__((packed, aligned(2))) USB_SetupPacket_t;
#define USB_BTABLE_ENTRIES \
((volatile USB_BufferTableEntry_t*)(USB_PMA_ADDR + USB_BTABLE_OFFSET))
typedef void (*USB_PacketHandler_t)(int length);
extern USB_PacketHandler_t USB_EP0OutPacketHandler;
void USB_Init(void);

349
stm32f103c8t6/src/usb_cdc.c Normal file
View file

@ -0,0 +1,349 @@
#include "usb_cdc.h"
#include "usb_util.h"
#include "led.h"
#include "config.h"
// Ring buffer for received data
static uint8_t USBCDC_RXBuffer[CONFIG_USB_RINGBUFFER_SIZE];
// Where the next received byte will be written to
static uint8_t *volatile USBCDC_RXBufferWrite = USBCDC_RXBuffer;
// Where the receive function reads the next byte from the buffer
static uint8_t *volatile USBCDC_RXBufferRead = USBCDC_RXBuffer;
// Is set true when the receive ring buffer is too full to hold another USB
// packet and the USB endpoint is halted.
static volatile bool USBCDC_RXSuspended = false;
// Ring buffer for data to be sent
static uint8_t USBCDC_TXBuffer[CONFIG_USB_RINGBUFFER_SIZE];
// Where the USB transmit procedure will read the next byte from
static uint8_t *volatile USBCDC_TXBufferRead = USBCDC_TXBuffer;
// Where the send routine will write the next byte into the buffer
static uint8_t *volatile USBCDC_TXBufferWrite = USBCDC_TXBuffer;
// True as long as a USB in transmission is ongoing. Is set to false in
// USBCDC_BuildInPacket() after an USB interrupt when the TX ring buffer is
// empty
static volatile bool USBCDC_TXTransferring = false;
USBCDC_LineCoding_t USBCDC_LineCoding =
{
.dwDTERate = 9600,
.bCharFormat = 0,
.bParityType = 0,
.bDataBits = 8
};
void USBCDC_InitEndpoints(void)
{
// Endpoint 1: Interrupt endpoint for notifications (buffer size 8)
USB_BTABLE_ENTRIES[1].COUNT_TX_0 = 0;
USB_BTABLE_ENTRIES[1].ADDR_TX_0 = 0xc0;
USB_SetEPR(&(USB->EP1R), USB_EPR_EP_TYPE_INTERRUPT
| USB_EPR_STAT_TX_NAK | USB_EPR_STAT_RX_DISABLED
| (1 << USB_EP1R_EA_Pos));
// Endpoint 2: Data in (buffer size 64)
USB_BTABLE_ENTRIES[2].COUNT_TX = 0;
USB_BTABLE_ENTRIES[2].ADDR_TX = 0x100;
USB_SetEPR(&(USB->EP2R), USB_EPR_EP_TYPE_BULK
| USB_EPR_STAT_TX_NAK | USB_EPR_STAT_RX_DISABLED
| (2 << USB_EP2R_EA_Pos));
// Endpoint 3: Data out (buffer size 64)
#if USBCDC_ENDPOINT_SIZE == 64
USB_BTABLE_ENTRIES[3].COUNT_RX = USB_EP_RXCOUNT_BL_SIZE | (1 << 10);
#else
#error Endpoint size currently unsupported
#endif
USB_BTABLE_ENTRIES[3].ADDR_RX = 0x140;
USB_SetEPR(&(USB->EP3R), USB_EPR_EP_TYPE_BULK
| USB_EPR_STAT_TX_DISABLED | USB_EPR_STAT_RX_VALID
| (3 << USB_EP3R_EA_Pos));
}
void USBCDC_HandleLineCodingPacket(int length)
{
// Sanity check for packet length (the align byte is not counted here,
// because it is not transmitted)
if(length != sizeof(USBCDC_LineCoding_t) - 1)
{
__asm__ volatile("bkpt");
}
USB_PMAToMemory((uint8_t*)&USBCDC_LineCoding, USB_BTABLE_ENTRIES[0].ADDR_RX,
sizeof(USBCDC_LineCoding_t));
USB_EP0OutPacketHandler = NULL;
}
void USBCDC_HandleInterfaceSetup(USB_SetupPacket_t *sp,
const void **reply_data, int *reply_length, uint8_t *reply_response)
{
switch(sp->bRequest)
{
case USBCDC_REQ_GET_LINE_CODING:
*reply_data = (const uint8_t*)&USBCDC_LineCoding;
*reply_length = sizeof(USBCDC_LineCoding_t);
break;
case USBCDC_REQ_SET_LINE_CODING:
*reply_response = USB_EP_TX_VALID;
*reply_data = NULL;
// The line coding will be sent in a separate packet (which won't be
// a setup packet). We thus set a handler which will be called for
// the next out transaction on endpoint 0.
USB_EP0OutPacketHandler = USBCDC_HandleLineCodingPacket;
break;
case USBCDC_REQ_SET_CONTROL_LINE_STATE:
// Ignored at the moment. wValue contains the control signal bitmap:
// Bit 0 corresponds to DTR, bit 1 to RTS.
*reply_response = USB_EP_TX_VALID;
*reply_data = NULL;
break;
default:
// Not implemented
__asm__ volatile("bkpt");
*reply_response = USB_EP_TX_STALL;
*reply_data = NULL;
break;
}
}
void USBCDC_HandleDataOut(void)
{
// Use a local variable for the ring buffer write pointer to avoid the
// volatile access overhead (which is fine because the pointer isn't
// modified anywhere else
uint8_t *ring_buffer = USBCDC_RXBufferWrite;
// Copy packet from PMA into the ring buffer. Duplicating the code here is
// easier than reusing USB_PMAToMemory() because the PMA's addressing
// weirdness creates a lot of edge cases with the ring buffer wraparound.
int packet_length = USB_BTABLE_ENTRIES[3].COUNT_RX & 0x3ff;
uint16_t pma_offset = USB_BTABLE_ENTRIES[3].ADDR_RX;
uint8_t *pma = (uint8_t*)(USB_PMA_ADDR + 2 * pma_offset);
for(int i = 0; i < packet_length; i++)
{
*ring_buffer++ = *pma++;
if(ring_buffer >= USBCDC_RXBuffer + CONFIG_USB_RINGBUFFER_SIZE)
{
ring_buffer = USBCDC_RXBuffer;
}
if(i & 1)
{
pma += 2;
}
}
// Set the ring buffer write pointer one element past the last one written
// in this function
USBCDC_RXBufferWrite = ring_buffer;
// Determine the free space in the ring buffer and if another packet will
// fit in
int ring_buffer_space = USBCDC_RXBufferRead - USBCDC_RXBufferWrite - 1;
if(ring_buffer_space < 0)
{
ring_buffer_space += CONFIG_USB_RINGBUFFER_SIZE;
}
if(ring_buffer_space >= USBCDC_ENDPOINT_SIZE)
{
// Set EP3 ready for the next packet only when there is enough space in
// the ring buffer
USB_SetEPRXStatus(&(USB->EP3R), USB_EP_RX_VALID);
}
else
{
USB_SetEPRXStatus(&(USB->EP3R), USB_EP_RX_NAK);
USBCDC_RXSuspended = true;
}
}
int USBCDC_ReceiveData(void *buffer, int length)
{
int available = USBCDC_RXBufferWrite - USBCDC_RXBufferRead;
if(available < 0)
{
available += CONFIG_USB_RINGBUFFER_SIZE;
}
if(available < length)
{
length = available;
}
if(length <= 0)
{
return 0;
}
int buffer_length = length;
int until_wraparound = USBCDC_RXBuffer + CONFIG_USB_RINGBUFFER_SIZE
- USBCDC_RXBufferRead;
if(buffer_length >= until_wraparound)
{
memcpy(buffer, USBCDC_RXBufferRead, until_wraparound);
buffer_length -= until_wraparound;
buffer += until_wraparound;
USBCDC_RXBufferRead = USBCDC_RXBuffer;
}
memcpy(buffer, USBCDC_RXBufferRead, buffer_length);
USBCDC_RXBufferRead += buffer_length;
// If receiving has been suspended because the ring buffer is too full,
// resume if there is now enough space for another packet
if(USBCDC_RXSuspended)
{
int ring_buffer_free = USBCDC_RXBufferRead - USBCDC_RXBufferWrite - 1;
if(ring_buffer_free >= USBCDC_ENDPOINT_SIZE)
{
USB_SetEPRXStatus(&(USB->EP3R), USB_EP_RX_VALID);
USBCDC_RXSuspended = false;
}
}
return length;
}
// Build a USB in packet out of data from the transmit ring buffer and mark it
// valid for the host to fetch it
static void USBCDC_BuildInPacket(void)
{
// Wait while there's still data being transmitted
while(USB_BTABLE_ENTRIES[2].COUNT_TX);
int packet_length = 0;
int ring_buffer_bytes = USBCDC_TXBufferWrite - USBCDC_TXBufferRead;
if(ring_buffer_bytes < 0)
{
// Ring buffer read address is bigger than the write address, meaning
// the write has wrapped around. Let's first deal with the data until
// the end of the buffer
int until_wraparound = USBCDC_TXBuffer + CONFIG_USB_RINGBUFFER_SIZE
- USBCDC_TXBufferRead;
if(until_wraparound > USBCDC_ENDPOINT_SIZE)
{
// More bytes to be sent than there is space in the PMA buffer
packet_length = USBCDC_ENDPOINT_SIZE;
USB_MemoryToPMA(USB_BTABLE_ENTRIES[2].ADDR_TX, USBCDC_TXBufferRead,
packet_length);
USBCDC_TXBufferRead += packet_length;
}
else
{
// The rest of the buffer until the end of the ring buffer will fit
// into the PMA buffer, so we can transmit everything and reset the
// read pointer to the ring buffer's beginning.
packet_length = until_wraparound;
USB_MemoryToPMA(USB_BTABLE_ENTRIES[2].ADDR_TX, USBCDC_TXBufferRead,
packet_length);
USBCDC_TXBufferRead = USBCDC_TXBuffer;
}
}
else if(ring_buffer_bytes > 0)
{
// This /could/ have been an `if` instead of an `else if` to fill up
// the PMA buffer completely if the ring buffer contents wrap around and
// are larger than the PMA area if both parts are combined. However,
// the PMA area only supports 16-bit accesses and an unaligned read
// pointer would lead to problems at the wraparound boundary unless
// specially handeled. Just sending two packets here is way simpler
// than adding handling for all border cases.
if(ring_buffer_bytes > USBCDC_ENDPOINT_SIZE)
{
packet_length = USBCDC_ENDPOINT_SIZE;
}
else
{
packet_length = ring_buffer_bytes;
}
USB_MemoryToPMA(USB_BTABLE_ENTRIES[2].ADDR_TX, USBCDC_TXBufferRead,
packet_length);
USBCDC_TXBufferRead += packet_length;
}
if(packet_length != 0)
{
USBCDC_TXTransferring = true;
// Mark the in packet, which is now stored in PMA memory, as valid
USB_BTABLE_ENTRIES[2].COUNT_TX = packet_length;
USB_SetEPTXStatus(&(USB->EP2R), USB_EP_TX_VALID);
}
}
void USBCDC_SendData(const void *data, int length)
{
while(length > 0)
{
// Block until ring buffer is no longer full
int ring_buffer_space = 0;
while(ring_buffer_space == 0)
{
// The ring buffer is empty when read and write pointer are the
// same. It is considered full when the write pointer is one spot
// before the read pointer. One index is thus unused to make the
// distinction between empty and full possible.
ring_buffer_space = USBCDC_TXBufferRead - USBCDC_TXBufferWrite - 1;
if(ring_buffer_space < 0)
{
ring_buffer_space += CONFIG_USB_RINGBUFFER_SIZE;
}
}
// If more data is supplied than would fit in the ring buffer, copy as
// much as possible in this iteration.
int store_length = ring_buffer_space;
if(length < store_length)
{
store_length = length;
}
length -= store_length;
// If copying all data into the ring buffer needs a write pointer
// wraparound, copy the part before the ring buffer 'end' first
int until_wraparound = USBCDC_TXBuffer + CONFIG_USB_RINGBUFFER_SIZE
- USBCDC_TXBufferWrite;
if(store_length >= until_wraparound)
{
memcpy(USBCDC_TXBufferWrite, data, until_wraparound);
USBCDC_TXBufferWrite = USBCDC_TXBuffer;
store_length -= until_wraparound;
data += until_wraparound;
}
memcpy(USBCDC_TXBufferWrite, data, store_length);
USBCDC_TXBufferWrite += store_length;
data += store_length;
// If there isn't already data being transferred, the process has to be
// kicked off. The later USB packets will be built from the USB transfer
// complete interrupts.
if(!USBCDC_TXTransferring)
{
USBCDC_BuildInPacket();
}
}
}
void USBCDC_HandleDataInComplete(void)
{
if(USBCDC_TXBufferRead == USBCDC_TXBufferWrite)
{
USBCDC_TXTransferring = false;
}
else
{
USBCDC_BuildInPacket();
}
}

View file

@ -0,0 +1,48 @@
#pragma once
#include <string.h>
#include "usb.h"
// Class specific requests
#define USBCDC_REQ_SEND_ENCAPSULATED_COMMAND 0x00
#define USBCDC_REQ_GET_ENCAPSULATED_RESPONSE 0x01
#define USBCDC_REQ_SET_COMM_FEATURE 0x02
#define USBCDC_REQ_GET_COMM_FEATURE 0x03
#define USBCDC_REQ_CLEAR_COMM_FEATURE 0x04
#define USBCDC_REQ_SET_LINE_CODING 0x20
#define USBCDC_REQ_GET_LINE_CODING 0x21
#define USBCDC_REQ_SET_CONTROL_LINE_STATE 0x22
#define USBCDC_REQ_SEND_BREAK 0x23
#define USBCDC_ENDPOINT_SIZE 64
typedef struct
{
uint32_t dwDTERate; // Data terminal rate, in baud
uint8_t bCharFormat; // 0: 1 stop bit, 1: 1.5 stop bits, 2: 2 stop bits
uint8_t bParityType; // 0: none, 1: odd, 2: even, 3: mark, 4: space
uint8_t bDataBits; // 5, 6, 7, 8 or 16
uint8_t align; // The PMA only supports word access
} __attribute__((packed)) USBCDC_LineCoding_t;
// Initialises the endpoints used by the virtual COM port after a reset
void USBCDC_InitEndpoints(void);
// Handler for USB interface setup packets
void USBCDC_HandleInterfaceSetup(USB_SetupPacket_t *sp,
const void **reply_data, int *reply_length, uint8_t *reply_response);
// Handler for USB out packets directed to the virtual COM port's out endpoint
void USBCDC_HandleDataOut(void);
// Handler for the successful transmission of an USB in packet
void USBCDC_HandleDataInComplete(void);
// Send data over the virtual COM port. This routine will block if there is more
// data to be sent than remaining space in the transmit ring buffer.
void USBCDC_SendData(const void *data, int length);
// Writes received data into a buffer. Returns the number of bytes written into
// the buffer.
int USBCDC_ReceiveData(void *buffer, int length);

View file

@ -0,0 +1,244 @@
#include "usb_descriptors.h"
const USB_DeviceDescriptor_t USB_DeviceDescriptor =
{
.bLength = sizeof(USB_DeviceDescriptor_t),
.bDescriptorType = USB_DEVICE_DESCRIPTOR,
.bcdUSB = 0x0200,
.bDeviceClass = 0x02, // CDC
.bDeviceSubClass = 0x00, // Subclass per interface
.bDeviceProtocol = 0x00, // Protocol per interface
.bMaxPacketSize0 = 64,
.idVendor = 0x16c0,
.idProduct = 0x05dc,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1
};
const USB_WholeDescriptor_t USB_ConfigurationInterfaceDescriptor =
{
.configuration = (USB_ConfigurationDescriptor_t)
{
.bLength = sizeof(USB_ConfigurationDescriptor_t),
.bDescriptorType = USB_CONFIGURATION_DESCRIPTOR,
.wTotalLength = sizeof(USB_WholeDescriptor_t),
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 100
},
// Interface 0: Control
.control_interface = (USB_InterfaceDescriptor_t)
{
.bLength = sizeof(USB_InterfaceDescriptor_t),
.bDescriptorType = USB_INTERFACE_DESCRIPTOR,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = 0x02, // CDC
.bInterfaceSubClass = 0x02, // ACM
.bInterfaceProtocol = 0x00, // No command protocol
.iInterface = 0
},
.control_interface_functional_header = (USB_HeaderFunctionalDescriptor_t)
{
.bFunctionLength = sizeof(USB_HeaderFunctionalDescriptor_t),
.bDescriptorType = USB_CLASS_SPECIFIC_INTERFACE_DESCRIPTOR,
.bDescriptorSubtype = 0x00, // Header subtype
.bcdCDC = 0x0120 // TODO: Check differences between 0x0110
// and 0x0120 (CDC 1.1 vs. CDC 1.2)
},
.control_interface_functional_acm = (USB_ACMFunctionalDescriptor_t)
{
.bFunctionLength = sizeof(USB_ACMFunctionalDescriptor_t),
.bDescriptorType = USB_CLASS_SPECIFIC_INTERFACE_DESCRIPTOR,
.bDescriptorSubtype = 0x02, // ACM
.bmCapabilities = 0x02 // Device supports Set_Line_Coding,
// Set_Control_Line_State, Get_Line_Coding,
// and the notification Serial_State
},
.control_interface_functional_unit = (USB_UnionFunctionalDescriptor_t)
{
.bFunctionLength = sizeof(USB_UnionFunctionalDescriptor_t),
.bDescriptorType = USB_CLASS_SPECIFIC_INTERFACE_DESCRIPTOR,
.bDescriptorSubtype = 0x06, // Union descriptor
.bControlInterface = 0, // Current interface
.bSubordinateInterface0 = 1 // Next interface for the actual data
},
// Endpoint 1: Notification (in)
.notification_endpoint = (USB_EndpointDescriptor_t)
{
.bLength = sizeof(USB_EndpointDescriptor_t),
.bDescriptorType = USB_ENDPOINT_DESCRIPTOR,
.bEndpointAddress = USB_ENDPOINT_IN | 1,
.bmAttributes = USB_ENDPOINT_INTERRUPT | USB_ENDPOINT_NO_SYNCHRONIZATION
| USB_ENDPOINT_DATA,
.wMaxPacketSize = 8,
.bInterval = 0xff
},
// Interface 1: Data
.data_interface = (USB_InterfaceDescriptor_t)
{
.bLength = sizeof(USB_InterfaceDescriptor_t),
.bDescriptorType = USB_INTERFACE_DESCRIPTOR,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = 0x0a, // CDC data class
.bInterfaceSubClass = 0x00, // No subclass
.bInterfaceProtocol = 0x00, // No data protocol
.iInterface = 0
},
// Endpoint 3: Data out
.data_out_endpoint = (USB_EndpointDescriptor_t)
{
.bLength = sizeof(USB_EndpointDescriptor_t),
.bDescriptorType = USB_ENDPOINT_DESCRIPTOR,
.bEndpointAddress = USB_ENDPOINT_OUT | 3,
.bmAttributes = USB_ENDPOINT_BULK | USB_ENDPOINT_NO_SYNCHRONIZATION
| USB_ENDPOINT_DATA,
.wMaxPacketSize = 64,
.bInterval = 0x05
},
// Endpoint 2: Data in
.data_in_endpoint = (USB_EndpointDescriptor_t)
{
.bLength = sizeof(USB_EndpointDescriptor_t),
.bDescriptorType = USB_ENDPOINT_DESCRIPTOR,
.bEndpointAddress = USB_ENDPOINT_IN | 2,
.bmAttributes = USB_ENDPOINT_BULK | USB_ENDPOINT_NO_SYNCHRONIZATION
| USB_ENDPOINT_DATA,
.wMaxPacketSize = 64,
.bInterval = 0x05
},
};
#define USB_STRING_LANGID 0x0409
#define USB_STRING_VENDOR \
'2', '5', '1', '2', '0'
#define USB_STRING_PRODUCT \
'H', 'P', 'G', 'L', ' ', 'X', 'Y'
const uint16_t USB_StringDescriptor_LangID[] =
USB_BUILD_STRING_DESCRIPTOR(USB_STRING_LANGID);
const uint16_t USB_StringDescriptor_Vendor[] =
USB_BUILD_STRING_DESCRIPTOR(USB_STRING_VENDOR);
const uint16_t USB_StringDescriptor_Product[] =
USB_BUILD_STRING_DESCRIPTOR(USB_STRING_PRODUCT);
void USB_HandleGetDescriptor(USB_DescriptorType_t descriptor_type,
int descriptor_index, const void **reply_data, int *reply_length,
uint8_t *reply_response)
{
switch(descriptor_type)
{
case USB_DEVICE_DESCRIPTOR:
*reply_data = &USB_DeviceDescriptor;
*reply_length = USB_DeviceDescriptor.bLength;
break;
case USB_CONFIGURATION_DESCRIPTOR:
*reply_data = &USB_ConfigurationInterfaceDescriptor;
if(*reply_length < USB_ConfigurationInterfaceDescriptor
.configuration.wTotalLength)
{
*reply_length = USB_ConfigurationInterfaceDescriptor
.configuration.bLength;
}
else
{
*reply_length = USB_ConfigurationInterfaceDescriptor
.configuration.wTotalLength;
}
break;
case USB_STRING_DESCRIPTOR:
switch(descriptor_index)
{
case 0:
*reply_data = (uint8_t*)USB_StringDescriptor_LangID;
*reply_length = (uint8_t)*USB_StringDescriptor_LangID;
break;
case 1:
*reply_data = (uint8_t*)USB_StringDescriptor_Vendor;
*reply_length = (uint8_t)*USB_StringDescriptor_Vendor;
break;
case 2:
*reply_data = (uint8_t*)USB_StringDescriptor_Product;
*reply_length = (uint8_t)*USB_StringDescriptor_Product;
break;
case 3:;
// Serial string
// The first two bytes are occupied by descriptor length and
// descriptor type (3 = string descriptor). String
// descriptors are 16 bits per char and are not zero-
// terminated, so we're reserving a buffer for 24 characters
// here.
static uint16_t buff[25];
// The first byte is the total length in bytes, the second
// byte is the descriptor type (3)
buff[0] = sizeof(buff) | (USB_STRING_DESCRIPTOR << 8);
// The unique device ID is 96 bits = 12 bytes long
for(int i = 0; i < 12; i++)
{
uint8_t uid_byte = *((uint8_t*)UID_BASE + i);
// We're using one of the first 16 letters of the
// alphabet for each nibble, just like in the bootloader
buff[1 + 2 * i] = 'A' + (uid_byte & 0x0f);
buff[2 + 2 * i] = 'A' + (uid_byte >> 4);
}
*reply_data = (uint8_t*)buff;
*reply_length = (uint8_t)*buff;
break;
default:
__asm__ volatile("bkpt");
}
break;
case USB_INTERFACE_DESCRIPTOR:
switch(descriptor_index)
{
case 0:
*reply_data = &USB_ConfigurationInterfaceDescriptor
.control_interface;
*reply_length = USB_ConfigurationInterfaceDescriptor
.control_interface.bLength;
break;
case 1:
*reply_data = &USB_ConfigurationInterfaceDescriptor
.data_interface;
*reply_length = USB_ConfigurationInterfaceDescriptor
.data_interface.bLength;
break;
default:
__asm__ volatile("bkpt");
}
break;
case USB_DEVICE_QUALIFIER_DESCRIPTOR:
// Device is full-speed only, so it must return a request error
*reply_response = USB_EP_TX_STALL;
*reply_data = NULL;
break;
case USB_ENDPOINT_DESCRIPTOR:
case USB_OTHER_DESCRIPTOR:
case USB_INTERFACE_POWER_DESCRIPTOR:
case USB_INTERFACE_ASSOCIATION_DESCRIPTOR:
case USB_CLASS_SPECIFIC_INTERFACE_DESCRIPTOR:
case USB_CLASS_SPECIFIC_ENDPOINT_DESCRIPTOR:
// Not implemented
__asm__ volatile("bkpt");
break;
}
}

View file

@ -0,0 +1,150 @@
#pragma once
#include <stdint.h>
#include <stddef.h>
#include "stm32f103x6.h"
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bcdUSB;
uint8_t bDeviceClass;
uint8_t bDeviceSubClass;
uint8_t bDeviceProtocol;
uint8_t bMaxPacketSize0;
uint16_t idVendor;
uint16_t idProduct;
uint16_t bcdDevice;
uint8_t iManufacturer;
uint8_t iProduct;
uint8_t iSerialNumber;
uint8_t bNumConfigurations;
} __attribute__((packed, aligned(1))) USB_DeviceDescriptor_t;
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumInterfaces;
uint8_t bConfigurationValue;
uint8_t iConfiguration;
uint8_t bmAttributes;
uint8_t bMaxPower;
} __attribute__((packed, aligned(1))) USB_ConfigurationDescriptor_t;
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bInterfaceNumber;
uint8_t bAlternateSetting;
uint8_t bNumEndpoints;
uint8_t bInterfaceClass;
uint8_t bInterfaceSubClass;
uint8_t bInterfaceProtocol;
uint8_t iInterface;
} __attribute__((packed, aligned(1))) USB_InterfaceDescriptor_t;
typedef struct
{
uint8_t bFunctionLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint16_t bcdCDC;
} __attribute__((packed, aligned(1))) USB_HeaderFunctionalDescriptor_t;
typedef struct
{
uint8_t bFunctionLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bControlInterface;
uint8_t bSubordinateInterface0;
} __attribute__((packed, aligned(1))) USB_UnionFunctionalDescriptor_t;
typedef union
{
struct
{
uint8_t bFunctionLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bmCapabilities;
} __attribute__((packed, aligned(1)));
uint8_t raw[4];
} __attribute__((packed, aligned(1))) USB_ACMFunctionalDescriptor_t;
// Endpoint direction for the bEndpointAddress field
#define USB_ENDPOINT_OUT 0x00
#define USB_ENDPOINT_IN 0x80
// Flags in bmAttributes
#define USB_ENDPOINT_CONTROL 0x00
#define USB_ENDPOINT_ISOCHRONOUS 0x01
#define USB_ENDPOINT_BULK 0x02
#define USB_ENDPOINT_INTERRUPT 0x03
#define USB_ENDPOINT_NO_SYNCHRONIZATION 0x00
#define USB_ENDPOINT_ASYNCHRONOUS 0x04
#define USB_ENDPOINT_ADAPTIVE 0x08
#define USB_ENDPOINT_SYNCHRONOUS 0x0c
#define USB_ENDPOINT_DATA 0x00
#define USB_ENDPOINT_FEEDBACK 0x10
#define USB_ENDPOINT_IMPLICIT_FEEDBACK_DATA 0x20
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
} __attribute__((packed, aligned(1))) USB_EndpointDescriptor_t;
typedef struct
{
USB_ConfigurationDescriptor_t configuration;
USB_InterfaceDescriptor_t control_interface;
USB_HeaderFunctionalDescriptor_t control_interface_functional_header;
USB_ACMFunctionalDescriptor_t control_interface_functional_acm;
USB_UnionFunctionalDescriptor_t control_interface_functional_unit;
USB_EndpointDescriptor_t notification_endpoint;
USB_InterfaceDescriptor_t data_interface;
USB_EndpointDescriptor_t data_out_endpoint;
USB_EndpointDescriptor_t data_in_endpoint;
} __attribute__((packed, aligned(1))) USB_WholeDescriptor_t;
typedef enum
{
USB_DEVICE_DESCRIPTOR = 0x01,
USB_CONFIGURATION_DESCRIPTOR = 0x02,
USB_STRING_DESCRIPTOR = 0x03,
USB_INTERFACE_DESCRIPTOR = 0x04,
USB_ENDPOINT_DESCRIPTOR = 0x05,
USB_DEVICE_QUALIFIER_DESCRIPTOR = 0x06,
USB_OTHER_DESCRIPTOR = 0x07,
USB_INTERFACE_POWER_DESCRIPTOR = 0x08,
USB_INTERFACE_ASSOCIATION_DESCRIPTOR = 0x0b,
USB_CLASS_SPECIFIC_INTERFACE_DESCRIPTOR = 0x24,
USB_CLASS_SPECIFIC_ENDPOINT_DESCRIPTOR = 0x25
} __attribute__((packed)) USB_DescriptorType_t;
#define USB_STRING_DESCRIPTOR_LENGTH(...) \
(sizeof((uint16_t[]){__VA_ARGS__}) + 2)
#define USB_BUILD_STRING_DESCRIPTOR(...) \
{USB_STRING_DESCRIPTOR_LENGTH(__VA_ARGS__) \
| (USB_STRING_DESCRIPTOR << 8), __VA_ARGS__}
void USB_HandleGetDescriptor(USB_DescriptorType_t descriptor_type,
int descriptor_index, const void **reply_data, int *reply_length,
uint8_t *reply_response);

View file

@ -0,0 +1,38 @@
#include "usb_util.h"
void USB_PMAToMemory(void *mem, uint16_t offset, size_t length)
{
uint8_t *dst = (uint8_t*)mem;
uint8_t *pma = (uint8_t*)(USB_PMA_ADDR + 2 * offset);
for(unsigned int i = 0; i < length; i++)
{
*dst++ = *pma++;
if(i & 1)
{
pma += 2;
}
}
}
void USB_MemoryToPMA(uint16_t offset, const void *mem, size_t length)
{
// Only words can be copied. Thus, if the length is not even, it has to be
// incremented to ensure that the last byte is copied. Since the PMA buffer
// always has even size, this is not a problem.
if(length & 1)
{
length++;
}
const uint8_t *src = (const uint8_t*)mem;
uint16_t *pma = (uint16_t*)(USB_PMA_ADDR + 2 * offset);
for(unsigned int i = 0; i < length / 2; i++)
{
uint16_t tmp = src[2 * i] | (src[2 * i + 1] << 8);
*pma++ = tmp;
pma++;
}
}

View file

@ -0,0 +1,91 @@
#pragma once
#include "usb.h"
static inline void USB_SetEPR(volatile uint16_t *EPR, uint16_t status)
{
// Caution: This function does a read-modify-write and is prone to
// unexpected behaviour when there are transactions going one, because the
// register contents might change during the funciton's execution. Thus,
// only use this function in initialisation code!
volatile uint16_t v = *EPR;
status ^= v & (USB_EP0R_DTOG_RX | USB_EP0R_STAT_RX |\
USB_EP0R_DTOG_TX | USB_EP0R_STAT_TX);
*EPR = status;
}
static inline void USB_SetEPRXStatus(volatile uint16_t *EPR, uint16_t status)
{
uint16_t v = *EPR;
v ^= status & USB_EP0R_STAT_RX;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND | USB_EP0R_CTR_TX
| USB_EP0R_EA | USB_EP0R_STAT_RX;
*EPR = v;
}
static inline void USB_SetEPTXStatus(volatile uint16_t *EPR, uint16_t status)
{
uint16_t v = *EPR;
v ^= status & USB_EP0R_STAT_TX;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND | USB_EP0R_CTR_TX
| USB_EP0R_EA | USB_EP0R_STAT_TX;
*EPR = v;
}
static inline void USB_SetEPType(volatile uint16_t *EPR, uint16_t type)
{
uint16_t v = *EPR;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_KIND | USB_EP0R_CTR_TX | USB_EP0R_EA;
v |= USB_EP0R_EP_TYPE & type;
*EPR = v;
}
static inline void USB_SetEPAddress(volatile uint16_t *EPR, uint16_t address)
{
uint16_t v = *EPR;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND
| USB_EP0R_CTR_TX;
v |= USB_EP0R_EA & address;
*EPR = v;
}
static inline void USB_SetEPKind(volatile uint16_t *EPR)
{
uint16_t v = *EPR;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_CTR_TX | USB_EP0R_EA;
v |= USB_EP0R_EP_KIND;
*EPR = v;
}
static inline void USB_ClearEPKind(volatile uint16_t *EPR)
{
uint16_t v = *EPR;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_CTR_TX | USB_EP0R_EA;
*EPR = v;
}
static inline void USB_ClearEPCTRX(volatile uint16_t *EPR)
{
uint16_t v = *EPR;
v &= USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND | USB_EP0R_CTR_TX | USB_EP0R_EA;
*EPR = v;
}
static inline void USB_ClearEPCTTX(volatile uint16_t *EPR)
{
uint16_t v = *EPR;
v &= USB_EP0R_CTR_RX | USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND | USB_EP0R_EA;
*EPR = v;
}
static inline void USB_Delay(unsigned int delay)
{
SysTick->LOAD = delay;
SysTick->VAL = 0;
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_ENABLE_Msk;
while(!((SysTick->CTRL) & SysTick_CTRL_COUNTFLAG_Msk));
SysTick->CTRL = 0;
}
void USB_PMAToMemory(void *mem, uint16_t offset, size_t length);
void USB_MemoryToPMA(uint16_t offset, const void *mem, size_t length);

View file

@ -0,0 +1,20 @@
#include "usb_vendor.h"
void USBVendor_HandleDeviceSetup(USB_SetupPacket_t *sp,
const void **reply_data, int *reply_length, uint8_t *reply_response)
{
USBVendor_Command_t command = sp->bRequest;
*reply_data = NULL;
*reply_length = 0;
switch(command)
{
case USB_VENDOR_COMMAND_NOP:
*reply_response = USB_EP_TX_VALID;
break;
default:
*reply_response = USB_EP_TX_STALL;
}
}

View file

@ -0,0 +1,11 @@
#pragma once
#include "usb.h"
typedef enum
{
USB_VENDOR_COMMAND_NOP = 0x00,
} USBVendor_Command_t;
void USBVendor_HandleDeviceSetup(USB_SetupPacket_t *sp,
const void **reply_data, int *reply_length, uint8_t *reply_response);