mirror of
https://github.com/cesanta/mongoose.git
synced 2024-11-28 05:39:00 +08:00
commit
5152ed8731
57
examples/ti/ek-tm4c1294xl-rndis/Makefile
Normal file
57
examples/ti/ek-tm4c1294xl-rndis/Makefile
Normal file
@ -0,0 +1,57 @@
|
||||
CFLAGS = -W -Wall -Wextra -Werror -Wundef -Wshadow -Wdouble-promotion
|
||||
CFLAGS += -Wformat-truncation -fno-common -Wconversion -Wno-sign-conversion
|
||||
CFLAGS += -g3 -Os -ffunction-sections -fdata-sections
|
||||
CFLAGS += -I. -Icmsis_core/CMSIS/Core/Include -Icmsis_tm4c/Device/TI/TM4C/Include
|
||||
CFLAGS += -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
LDFLAGS ?= -Tlink.ld -nostdlib -nostartfiles --specs nano.specs -lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map
|
||||
|
||||
SOURCES = main.c syscalls.c sysinit.c
|
||||
SOURCES += startup.c # startup file. Compiler-dependent!
|
||||
|
||||
# TinyUSB
|
||||
SOURCES += tinyusb/src/tusb.c
|
||||
SOURCES += tinyusb/src/common/tusb_fifo.c
|
||||
SOURCES += tinyusb/src/device/usbd.c
|
||||
SOURCES += tinyusb/src/device/usbd_control.c
|
||||
SOURCES += tinyusb/src/class/net/ecm_rndis_device.c
|
||||
SOURCES += tinyusb/src/class/net/ncm_device.c
|
||||
SOURCES += tinyusb/src/portable/mentor/musb/dcd_musb.c
|
||||
SOURCES += tinyusb/lib/networking/rndis_reports.c
|
||||
SOURCES += usb_descriptors.c
|
||||
CFLAGS += -Itinyusb/src -Itinyusb/lib/networking
|
||||
CFLAGS += -DTM4C1294NCPDT
|
||||
CFLAGS += -Wno-conversion -Wno-sign-conversion
|
||||
|
||||
# Mongoose-specific. See https://mongoose.ws/documentation/#build-options
|
||||
SOURCES += mongoose.c
|
||||
CFLAGS += -DMG_ENABLE_TCPIP=1 -DMG_ARCH=MG_ARCH_NEWLIB -DMG_ENABLE_CUSTOM_MILLIS=1
|
||||
CFLAGS += -DMG_IO_SIZE=512 $(CFLAGS_EXTRA)
|
||||
|
||||
ifeq ($(OS),Windows_NT)
|
||||
RM = cmd /C del /Q /F /S
|
||||
else
|
||||
RM = rm -rf
|
||||
endif
|
||||
|
||||
all build example: firmware.bin
|
||||
|
||||
firmware.bin: firmware.elf
|
||||
arm-none-eabi-objcopy -O binary $< $@
|
||||
|
||||
firmware.elf: cmsis_core cmsis_tm4c tinyusb $(SOURCES) hal.h link.ld
|
||||
arm-none-eabi-gcc $(SOURCES) $(CFLAGS) $(LDFLAGS) -o $@
|
||||
|
||||
flash: firmware.bin
|
||||
@echo "This requires Uniflash"
|
||||
|
||||
cmsis_core: # ARM CMSIS core headers
|
||||
git clone --depth 1 -b 5.9.0 https://github.com/ARM-software/CMSIS_5 $@
|
||||
cmsis_tm4c: # CMSIS headers for TM4C series
|
||||
git clone --depth 1 --no-checkout https://github.com/speters/CMSIS $@ && cd $@ && git sparse-checkout set Device/TI/TM4C && git checkout
|
||||
cd cmsis_tm4c && git apply ../cmsis_tm4c.patch # Fix error for the device we tested
|
||||
tinyusb: # TinyUSB sources
|
||||
git clone --depth 1 -b 0.14.0 https://github.com/hathach/tinyusb $@
|
||||
cd tinyusb && git apply ../tinyusb.patch # Enable support for TM4C129 series
|
||||
|
||||
clean:
|
||||
$(RM) firmware.* *.su cmsis_core cmsis_tm4c tinyusb
|
13
examples/ti/ek-tm4c1294xl-rndis/cmsis_tm4c.patch
Normal file
13
examples/ti/ek-tm4c1294xl-rndis/cmsis_tm4c.patch
Normal file
@ -0,0 +1,13 @@
|
||||
diff --git a/Device/TI/TM4C/Include/TM4C1294NCPDT.h b/Device/TI/TM4C/Include/TM4C1294NCPDT.h
|
||||
index d2e48b4..cb1a843 100644
|
||||
--- a/Device/TI/TM4C/Include/TM4C1294NCPDT.h
|
||||
+++ b/Device/TI/TM4C/Include/TM4C1294NCPDT.h
|
||||
@@ -841,7 +841,7 @@ typedef struct { /*!< USB0 Structure
|
||||
__O uint8_t CSRL0; /*!< USB Control and Status Endpoint 0 Low */
|
||||
};
|
||||
__O uint8_t CSRH0; /*!< USB Control and Status Endpoint 0 High */
|
||||
- __I uint16_t RESERVED24[3];
|
||||
+ __I uint16_t RESERVED24[2];
|
||||
__IO uint8_t COUNT0; /*!< USB Receive Byte Count Endpoint 0 */
|
||||
__I uint8_t RESERVED25[1];
|
||||
__IO uint8_t TYPE0; /*!< USB Type Endpoint 0 */
|
181
examples/ti/ek-tm4c1294xl-rndis/hal.h
Normal file
181
examples/ti/ek-tm4c1294xl-rndis/hal.h
Normal file
@ -0,0 +1,181 @@
|
||||
// Copyright (c) 2022 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
// https://www.ti.com/lit/pdf/spms433
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "TM4C1294NCPDT.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
#define BIT(x) (1UL << (x))
|
||||
#define SETBITS(R, CLEARMASK, SETMASK) (R) = ((R) & ~(CLEARMASK)) | (SETMASK)
|
||||
#define PIN(bank, num) ((bank << 8) | (num))
|
||||
#define PINNO(pin) (pin & 255)
|
||||
#define PINBANK(pin) pinbank(pin >> 8)
|
||||
// This MCU doesn't have GPIOI nor GPIOO
|
||||
static inline unsigned int pinbank(unsigned int bank) {
|
||||
bank = bank > 'O' ? bank - 2 : bank > 'I' ? bank - 1 : bank;
|
||||
return bank - 'A';
|
||||
}
|
||||
|
||||
// 5.5, Table 5-12: configure flash (and EEPROM) timing in accordance to clock
|
||||
// freq
|
||||
enum {
|
||||
PLL_CLK = 25,
|
||||
PLL_M = 96,
|
||||
PLL_N = 5,
|
||||
PLL_Q = 1,
|
||||
PSYSDIV = 4
|
||||
}; // Run at 120 Mhz
|
||||
#define PLL_FREQ (PLL_CLK * PLL_M / PLL_N / PLL_Q / PSYSDIV)
|
||||
#define FLASH_CLKHIGH 6
|
||||
#define FLASH_WAITST 5
|
||||
#define SYS_FREQUENCY (PLL_FREQ * 1000000)
|
||||
|
||||
static inline void spin(volatile uint32_t count) {
|
||||
while (count--) (void) 0;
|
||||
}
|
||||
|
||||
enum { GPIO_MODE_INPUT, GPIO_MODE_OUTPUT, GPIO_MODE_AF, GPIO_MODE_ANALOG };
|
||||
enum { GPIO_OTYPE_PUSH_PULL, GPIO_OTYPE_OPEN_DRAIN };
|
||||
enum { GPIO_SPEED_LOW, GPIO_SPEED_HIGH };
|
||||
enum { GPIO_PULL_NONE, GPIO_PULL_UP, GPIO_PULL_DOWN };
|
||||
#define GPIO(bank) ((GPIOA_AHB_Type *) (GPIOA_AHB_BASE + 0x1000U * (bank)))
|
||||
|
||||
// CMSIS header forces 0xFF mask when writing to DATA (see 10.6 in datasheet)
|
||||
// and does not seem to support that feature for writing by defining RESERVED0
|
||||
// to read-only
|
||||
static inline void gpio_toggle(uint16_t pin) {
|
||||
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
|
||||
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
|
||||
uint8_t mask = BIT(PINNO(pin));
|
||||
GPIODATA[mask] ^= mask;
|
||||
}
|
||||
static inline int gpio_read(uint16_t pin) {
|
||||
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
|
||||
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
|
||||
uint8_t mask = BIT(PINNO(pin));
|
||||
return GPIODATA[mask] ? 1 : 0;
|
||||
}
|
||||
static inline void gpio_write(uint16_t pin, bool val) {
|
||||
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
|
||||
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
|
||||
uint8_t mask = BIT(PINNO(pin));
|
||||
GPIODATA[mask] = val ? mask : 0;
|
||||
}
|
||||
static inline void gpio_init(uint16_t pin, uint8_t mode, uint8_t type,
|
||||
uint8_t speed, uint8_t pull, uint8_t af) {
|
||||
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
|
||||
uint8_t n = (uint8_t) (PINNO(pin));
|
||||
SYSCTL->RCGCGPIO |= BIT(PINBANK(pin)); // Enable GPIO clock
|
||||
if (mode == GPIO_MODE_ANALOG) {
|
||||
gpio->AMSEL |= BIT(PINNO(pin));
|
||||
return;
|
||||
}
|
||||
if (mode == GPIO_MODE_INPUT) {
|
||||
gpio->DIR &= ~BIT(PINNO(pin));
|
||||
} else if (mode == GPIO_MODE_OUTPUT) {
|
||||
gpio->DIR |= BIT(PINNO(pin));
|
||||
} else { // GPIO_MODE_AF
|
||||
SETBITS(gpio->PCTL, 15UL << ((n & 7) * 4),
|
||||
((uint32_t) af) << ((n & 7) * 4));
|
||||
gpio->AFSEL |= BIT(PINNO(pin));
|
||||
}
|
||||
gpio->DEN |= BIT(PINNO(pin)); // Enable pin as digital function
|
||||
if (type == GPIO_OTYPE_OPEN_DRAIN)
|
||||
gpio->ODR |= BIT(PINNO(pin));
|
||||
else // GPIO_OTYPE_PUSH_PULL
|
||||
gpio->ODR &= ~BIT(PINNO(pin));
|
||||
if (speed == GPIO_SPEED_LOW)
|
||||
gpio->SLR |= BIT(PINNO(pin));
|
||||
else // GPIO_SPEED_HIGH
|
||||
gpio->SLR &= ~BIT(PINNO(pin));
|
||||
if (pull == GPIO_PULL_UP) {
|
||||
gpio->PUR |= BIT(PINNO(pin)); // setting one...
|
||||
} else if (pull == GPIO_PULL_DOWN) {
|
||||
gpio->PDR |= BIT(PINNO(pin)); // ...just clears the other
|
||||
} else {
|
||||
gpio->PUR &= ~BIT(PINNO(pin));
|
||||
gpio->PDR &= ~BIT(PINNO(pin));
|
||||
}
|
||||
}
|
||||
static inline void gpio_input(uint16_t pin) {
|
||||
gpio_init(pin, GPIO_MODE_INPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
|
||||
GPIO_PULL_NONE, 0);
|
||||
}
|
||||
static inline void gpio_output(uint16_t pin) {
|
||||
gpio_init(pin, GPIO_MODE_OUTPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
|
||||
GPIO_PULL_NONE, 0);
|
||||
}
|
||||
|
||||
static inline void gpio_irq_attach(uint16_t pin) {
|
||||
uint8_t irqvecs[] = {16, 17, 18, 19, 20, 30, 31, 32,
|
||||
51, 52, 53, 72, 73, 76, 84};
|
||||
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
|
||||
gpio->IS &= ~BIT(PINNO(pin)); // edge sensitive
|
||||
gpio->IBE |= BIT(PINNO(pin)); // both edges
|
||||
gpio->IM |= BIT(PINNO(pin)); // enable pin irq
|
||||
int irqvec = irqvecs[PINBANK(pin)]; // IRQ vector index, 2.5.2
|
||||
NVIC_SetPriority(irqvec, 3);
|
||||
NVIC_EnableIRQ(irqvec);
|
||||
}
|
||||
|
||||
#ifndef UART_DEBUG
|
||||
#define UART_DEBUG UART0
|
||||
#endif
|
||||
|
||||
#define UART_OFFSET 0x1000
|
||||
#define UART(N) ((UART0_Type *) (UART0_BASE + UART_OFFSET * (N)))
|
||||
#define UARTNO(u) ((uint8_t) (((unsigned int) (u) -UART0_BASE) / UART_OFFSET))
|
||||
|
||||
static inline void uart_init(UART0_Type *uart, unsigned long baud) {
|
||||
uint8_t af = 1; // Alternate function
|
||||
uint16_t rx = 0, tx = 0; // pins
|
||||
uint8_t uartno = UARTNO(uart);
|
||||
|
||||
SYSCTL->RCGCUART |= BIT(uartno); // Enable peripheral clock
|
||||
|
||||
if (uart == UART0) tx = PIN('A', 0), rx = PIN('A', 1);
|
||||
if (uart == UART1) tx = PIN('B', 0), rx = PIN('B', 1);
|
||||
if (uart == UART2) tx = PIN('A', 6), rx = PIN('A', 7); // or PD4, PD5...
|
||||
|
||||
gpio_init(tx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, 0, af);
|
||||
gpio_init(rx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, 0, af);
|
||||
// (16.3.2) ClkDiv = 16 (HSE=0)
|
||||
// BRD = BRDI + BRDF = UARTSysClk / (ClkDiv * Baud Rate)
|
||||
// UARTFBRD[DIVFRAC] = integer(BRDF * 64 + 0.5)
|
||||
// must write in this order
|
||||
uart->CTL = 0; // Disable this UART, clear HSE
|
||||
uart->IBRD = SYS_FREQUENCY / (16 * baud); // Baud rate, integer part
|
||||
uart->FBRD = ((SYS_FREQUENCY % (16 * baud)) >> 26) &
|
||||
0x3F; // Baud rate, fractional part
|
||||
uart->LCRH = (3 << 5); // 8N1, no FIFOs;
|
||||
uart->CTL |= BIT(0) | BIT(9) | BIT(8); // Set UARTEN, RXE, TXE
|
||||
}
|
||||
static inline void uart_write_byte(UART0_Type *uart, uint8_t byte) {
|
||||
uart->DR = byte;
|
||||
while ((uart->FR & BIT(7)) == 0) spin(1);
|
||||
}
|
||||
static inline void uart_write_buf(UART0_Type *uart, char *buf, size_t len) {
|
||||
while (len-- > 0) uart_write_byte(uart, *(uint8_t *) buf++);
|
||||
}
|
||||
static inline int uart_read_ready(UART0_Type *uart) {
|
||||
return uart->FR & BIT(6); // If RXFF bit is set, data is ready
|
||||
}
|
||||
static inline uint8_t uart_read_byte(UART0_Type *uart) {
|
||||
return (uint8_t) (uart->DR & 0xFF);
|
||||
}
|
||||
|
||||
// Helper macro for reading pre-flashed MAC from user registers
|
||||
#define READ_PREFLASHED_MAC() \
|
||||
{ \
|
||||
(FLASH_CTRL->USERREG0 >> 0) & 0xFF, (FLASH_CTRL->USERREG0 >> 8) & 0xFF, \
|
||||
(FLASH_CTRL->USERREG0 >> 16) & 0xFF, \
|
||||
(FLASH_CTRL->USERREG1 >> 0) & 0xFF, \
|
||||
(FLASH_CTRL->USERREG1 >> 8) & 0xFF, \
|
||||
(FLASH_CTRL->USERREG1 >> 16) & 0xFF \
|
||||
}
|
29
examples/ti/ek-tm4c1294xl-rndis/link.ld
Normal file
29
examples/ti/ek-tm4c1294xl-rndis/link.ld
Normal file
@ -0,0 +1,29 @@
|
||||
ENTRY(Reset_Handler);
|
||||
MEMORY {
|
||||
flash(rx) : ORIGIN = 0x00000000, LENGTH = 1024k
|
||||
sram(rwx) : ORIGIN = 0x20000000, LENGTH = 256k
|
||||
}
|
||||
_estack = ORIGIN(sram) + LENGTH(sram); /* stack points to end of SRAM */
|
||||
|
||||
SECTIONS {
|
||||
.vectors : { KEEP(*(.vectors)) } > flash
|
||||
.text : { *(.text* .text.*) } > flash
|
||||
.rodata : { *(.rodata*) } > flash
|
||||
|
||||
.data : {
|
||||
_sdata = .; /* for init_ram() */
|
||||
*(.first_data)
|
||||
*(.data SORT(.data.*))
|
||||
_edata = .; /* for init_ram() */
|
||||
} > sram AT > flash
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
.bss : {
|
||||
_sbss = .; /* for init_ram() */
|
||||
*(.bss SORT(.bss.*) COMMON)
|
||||
_ebss = .; /* for init_ram() */
|
||||
} > sram
|
||||
|
||||
. = ALIGN(8);
|
||||
_end = .; /* for cmsis_gcc.h and init_ram() */
|
||||
}
|
129
examples/ti/ek-tm4c1294xl-rndis/main.c
Normal file
129
examples/ti/ek-tm4c1294xl-rndis/main.c
Normal file
@ -0,0 +1,129 @@
|
||||
// Copyright (c) 2022-2023 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
|
||||
#include "hal.h"
|
||||
#include "mongoose.h"
|
||||
#include "tusb.h"
|
||||
|
||||
#define LED1 PIN('N', 1) // On-board LED pin
|
||||
#define LED2 PIN('N', 0) // On-board LED pin
|
||||
#define LED3 PIN('F', 4) // On-board LED pin
|
||||
#define LED4 PIN('F', 0) // On-board LED pin
|
||||
|
||||
static struct mg_tcpip_if *s_ifp;
|
||||
const uint8_t tud_network_mac_address[6] = {2, 2, 0x84, 0x6A, 0x96, 0};
|
||||
|
||||
static void blink_cb(void *arg) { // Blink periodically
|
||||
gpio_toggle(LED1);
|
||||
(void) arg;
|
||||
}
|
||||
|
||||
static volatile uint64_t s_ticks; // Milliseconds since boot
|
||||
void SysTick_Handler(void) { // SyStick IRQ handler, triggered every 1ms
|
||||
s_ticks++;
|
||||
}
|
||||
|
||||
uint64_t mg_millis(void) { // Let Mongoose use our uptime function
|
||||
return s_ticks; // Return number of milliseconds since boot
|
||||
}
|
||||
|
||||
bool tud_network_recv_cb(const uint8_t *buf, uint16_t len) {
|
||||
mg_tcpip_qwrite((void *) buf, len, s_ifp);
|
||||
// MG_INFO(("RECV %hu", len));
|
||||
// mg_hexdump(buf, len);
|
||||
tud_network_recv_renew();
|
||||
return true;
|
||||
}
|
||||
|
||||
void tud_network_init_cb(void) {
|
||||
}
|
||||
|
||||
void USB0_Handler(void) { // USB interrupt handler
|
||||
tud_int_handler(0); // Pass control to TinyUSB
|
||||
}
|
||||
|
||||
uint16_t tud_network_xmit_cb(uint8_t *dst, void *ref, uint16_t arg) {
|
||||
// MG_INFO(("SEND %hu", arg));
|
||||
memcpy(dst, ref, arg);
|
||||
return arg;
|
||||
}
|
||||
|
||||
static size_t usb_tx(const void *buf, size_t len, struct mg_tcpip_if *ifp) {
|
||||
if (!tud_ready()) return 0;
|
||||
while (!tud_network_can_xmit(len)) tud_task();
|
||||
tud_network_xmit((void *) buf, len);
|
||||
(void) ifp;
|
||||
return len;
|
||||
}
|
||||
|
||||
static bool usb_up(struct mg_tcpip_if *ifp) {
|
||||
(void) ifp;
|
||||
return tud_inited() && tud_ready() && tud_connected();
|
||||
}
|
||||
|
||||
static void fn(struct mg_connection *c, int ev, void *ev_data, void *fn_data) {
|
||||
if (ev == MG_EV_HTTP_MSG) {
|
||||
struct mg_http_message *hm = (struct mg_http_message *) ev_data;
|
||||
if (mg_http_match_uri(hm, "/api/debug")) {
|
||||
int level = mg_json_get_long(hm->body, "$.level", MG_LL_DEBUG);
|
||||
mg_log_set(level);
|
||||
mg_http_reply(c, 200, "", "Debug level set to %d\n", level);
|
||||
} else {
|
||||
mg_http_reply(c, 200, "", "hi\n");
|
||||
}
|
||||
}
|
||||
(void) fn_data;
|
||||
}
|
||||
|
||||
int main(void) {
|
||||
gpio_output(LED1); // Setup blue LED
|
||||
uart_init(UART_DEBUG, 115200); // Initialise debug printf
|
||||
|
||||
struct mg_mgr mgr; // Initialise
|
||||
mg_mgr_init(&mgr); // Mongoose event manager
|
||||
mg_log_set(MG_LL_DEBUG); // Set log level
|
||||
|
||||
MG_INFO(("Init TCP/IP stack ..."));
|
||||
struct mg_tcpip_driver driver = {.tx = usb_tx, .up = usb_up};
|
||||
struct mg_tcpip_if mif = {.mac = {2, 0, 1, 2, 3, 0x77},
|
||||
.ip = mg_htonl(MG_U32(192, 168, 3, 1)),
|
||||
.mask = mg_htonl(MG_U32(255, 255, 255, 0)),
|
||||
.enable_dhcp_server = true,
|
||||
.driver = &driver,
|
||||
.recv_queue.size = 4096};
|
||||
s_ifp = &mif;
|
||||
mg_tcpip_init(&mgr, &mif);
|
||||
mg_timer_add(&mgr, 500, MG_TIMER_REPEAT, blink_cb, &mgr);
|
||||
mg_http_listen(&mgr, "tcp://0.0.0.0:80", fn, &mgr);
|
||||
|
||||
MG_INFO(("Init USB ..."));
|
||||
gpio_init(PIN('L', 6), GPIO_MODE_ANALOG, GPIO_OTYPE_PUSH_PULL,
|
||||
GPIO_SPEED_HIGH, GPIO_PULL_NONE, 0); // D_P
|
||||
gpio_init(PIN('L', 7), GPIO_MODE_ANALOG, GPIO_OTYPE_PUSH_PULL,
|
||||
GPIO_SPEED_HIGH, GPIO_PULL_NONE, 0); // D_N
|
||||
gpio_init(PIN('B', 1), GPIO_MODE_ANALOG, GPIO_OTYPE_PUSH_PULL,
|
||||
GPIO_SPEED_HIGH, GPIO_PULL_NONE, 0); // VBUS
|
||||
gpio_init(PIN('B', 0), GPIO_MODE_ANALOG, GPIO_OTYPE_PUSH_PULL,
|
||||
GPIO_SPEED_HIGH, GPIO_PULL_NONE, 0); // ID
|
||||
SYSCTL->RCGCUSB |= BIT(0); // Enable USB clock
|
||||
SYSCTL->SRUSB |= BIT(0); // Reset peripheral
|
||||
SYSCTL->SRUSB &= ~BIT(0);
|
||||
USB0->CC = 0x207; // Enable clock and configure divisor for 60MHz clock
|
||||
USB0->GPCS = 3;
|
||||
USB0->LPMCNTRL &= ~BIT(0);
|
||||
USB0->LPMCNTRL = 0;
|
||||
MG_INFO(("USB Controller version %d", 1 + (USB0->PP & 0xF)));
|
||||
MG_INFO(("IS: %x", USB0->IS));
|
||||
if (USB0->EPCISC & BIT(0)) // check PF flag,
|
||||
USB0->EPCISC |= BIT(0); // clear PF interrupt if so
|
||||
|
||||
tusb_init();
|
||||
|
||||
MG_INFO(("Init done, starting main loop ..."));
|
||||
for (;;) {
|
||||
mg_mgr_poll(&mgr, 0);
|
||||
tud_task();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
1
examples/ti/ek-tm4c1294xl-rndis/mongoose.c
Symbolic link
1
examples/ti/ek-tm4c1294xl-rndis/mongoose.c
Symbolic link
@ -0,0 +1 @@
|
||||
../../../mongoose.c
|
1
examples/ti/ek-tm4c1294xl-rndis/mongoose.h
Symbolic link
1
examples/ti/ek-tm4c1294xl-rndis/mongoose.h
Symbolic link
@ -0,0 +1 @@
|
||||
../../../mongoose.h
|
2
examples/ti/ek-tm4c1294xl-rndis/netif/ethernet.h
Normal file
2
examples/ti/ek-tm4c1294xl-rndis/netif/ethernet.h
Normal file
@ -0,0 +1,2 @@
|
||||
#pragma once
|
||||
#define SIZEOF_ETH_HDR 14
|
168
examples/ti/ek-tm4c1294xl-rndis/startup.c
Normal file
168
examples/ti/ek-tm4c1294xl-rndis/startup.c
Normal file
@ -0,0 +1,168 @@
|
||||
// Copyright (c) 2022 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
|
||||
// Startup code
|
||||
__attribute__((naked, noreturn)) void Reset_Handler(void) {
|
||||
// Initialise memory
|
||||
extern long _sbss, _ebss, _sdata, _edata, _sidata;
|
||||
for (long *src = &_sbss; src < &_ebss; src++) *src = 0;
|
||||
for (long *src = &_sdata, *dst = &_sidata; src < &_edata;) *src++ = *dst++;
|
||||
|
||||
// Call the clock system initialization function
|
||||
extern void SystemInit(void);
|
||||
SystemInit();
|
||||
// Call static constructors
|
||||
extern void __libc_init_array(void);
|
||||
__libc_init_array();
|
||||
// Call the application entry point
|
||||
extern void main(void);
|
||||
main();
|
||||
for (;;) (void) 0; // Infinite loop
|
||||
}
|
||||
|
||||
void __attribute__((weak)) DefaultIRQHandler(void) {
|
||||
for (;;) (void) 0;
|
||||
}
|
||||
#define WEAK_ALIAS __attribute__((weak, alias("DefaultIRQHandler")))
|
||||
|
||||
WEAK_ALIAS void NMI_Handler(void);
|
||||
WEAK_ALIAS void HardFault_Handler(void);
|
||||
WEAK_ALIAS void MemManage_Handler(void);
|
||||
WEAK_ALIAS void BusFault_Handler(void);
|
||||
WEAK_ALIAS void UsageFault_Handler(void);
|
||||
WEAK_ALIAS void SVC_Handler(void);
|
||||
WEAK_ALIAS void DebugMon_Handler(void);
|
||||
WEAK_ALIAS void PendSV_Handler(void);
|
||||
WEAK_ALIAS void SysTick_Handler(void);
|
||||
|
||||
WEAK_ALIAS void GPIOA_Handler(void);
|
||||
WEAK_ALIAS void GPIOB_Handler(void);
|
||||
WEAK_ALIAS void GPIOC_Handler(void);
|
||||
WEAK_ALIAS void GPIOD_Handler(void);
|
||||
WEAK_ALIAS void GPIOE_Handler(void);
|
||||
WEAK_ALIAS void UART0_Handler(void);
|
||||
WEAK_ALIAS void UART1_Handler(void);
|
||||
WEAK_ALIAS void SSI0_Handler(void);
|
||||
WEAK_ALIAS void I2C0_Handler(void);
|
||||
WEAK_ALIAS void PMW0_FAULT_Handler(void);
|
||||
WEAK_ALIAS void PWM0_0_Handler(void);
|
||||
WEAK_ALIAS void PWM0_1_Handler(void);
|
||||
WEAK_ALIAS void PWM0_2_Handler(void);
|
||||
WEAK_ALIAS void QEI0_Handler(void);
|
||||
WEAK_ALIAS void ADC0SS0_Handler(void);
|
||||
WEAK_ALIAS void ADC0SS1_Handler(void);
|
||||
WEAK_ALIAS void ADC0SS2_Handler(void);
|
||||
WEAK_ALIAS void ADC0SS3_Handler(void);
|
||||
WEAK_ALIAS void WDT0_Handler(void);
|
||||
WEAK_ALIAS void TIMER0A_Handler(void);
|
||||
WEAK_ALIAS void TIMER0B_Handler(void);
|
||||
WEAK_ALIAS void TIMER1A_Handler(void);
|
||||
WEAK_ALIAS void TIMER1B_Handler(void);
|
||||
WEAK_ALIAS void TIMER2A_Handler(void);
|
||||
WEAK_ALIAS void TIMER2B_Handler(void);
|
||||
WEAK_ALIAS void COMP0_Handler(void);
|
||||
WEAK_ALIAS void COMP1_Handler(void);
|
||||
WEAK_ALIAS void COMP2_Handler(void);
|
||||
WEAK_ALIAS void SYSCTL_Handler(void);
|
||||
WEAK_ALIAS void FLASH_Handler(void);
|
||||
WEAK_ALIAS void GPIOF_Handler(void);
|
||||
WEAK_ALIAS void GPIOG_Handler(void);
|
||||
WEAK_ALIAS void GPIOH_Handler(void);
|
||||
WEAK_ALIAS void UART2_Handler(void);
|
||||
WEAK_ALIAS void SSI1_Handler(void);
|
||||
WEAK_ALIAS void TIMER3A_Handler(void);
|
||||
WEAK_ALIAS void TIMER3B_Handler(void);
|
||||
WEAK_ALIAS void I2C1_Handler(void);
|
||||
WEAK_ALIAS void CAN0_Handler(void);
|
||||
WEAK_ALIAS void CAN1_Handler(void);
|
||||
WEAK_ALIAS void EMAC0_IRQHandler(void);
|
||||
WEAK_ALIAS void HIB_Handler(void);
|
||||
WEAK_ALIAS void USB0_Handler(void);
|
||||
WEAK_ALIAS void PWM0_3_Handler(void);
|
||||
WEAK_ALIAS void UDMA_Handler(void);
|
||||
WEAK_ALIAS void UDMAERR_Handler(void);
|
||||
WEAK_ALIAS void ADC1SS0_Handler(void);
|
||||
WEAK_ALIAS void ADC1SS1_Handler(void);
|
||||
WEAK_ALIAS void ADC1SS2_Handler(void);
|
||||
WEAK_ALIAS void ADC1SS3_Handler(void);
|
||||
WEAK_ALIAS void EPI0_Handler(void);
|
||||
WEAK_ALIAS void GPIOJ_Handler(void);
|
||||
WEAK_ALIAS void GPIOK_Handler(void);
|
||||
WEAK_ALIAS void GPIOL_Handler(void);
|
||||
WEAK_ALIAS void SSI2_Handler(void);
|
||||
WEAK_ALIAS void SSI3_Handler(void);
|
||||
WEAK_ALIAS void UART3_Handler(void);
|
||||
WEAK_ALIAS void UART4_Handler(void);
|
||||
WEAK_ALIAS void UART5_Handler(void);
|
||||
WEAK_ALIAS void UART6_Handler(void);
|
||||
WEAK_ALIAS void UART7_Handler(void);
|
||||
WEAK_ALIAS void I2C2_Handler(void);
|
||||
WEAK_ALIAS void I2C3_Handler(void);
|
||||
WEAK_ALIAS void TIMER4A_Handler(void);
|
||||
WEAK_ALIAS void TIMER4B_Handler(void);
|
||||
WEAK_ALIAS void TIMER5A_Handler(void);
|
||||
WEAK_ALIAS void TIMER5B_Handler(void);
|
||||
WEAK_ALIAS void FPU_Handler(void);
|
||||
WEAK_ALIAS void I2C4_Handler(void);
|
||||
WEAK_ALIAS void I2C5_Handler(void);
|
||||
WEAK_ALIAS void GPIOM_Handler(void);
|
||||
WEAK_ALIAS void GPION_Handler(void);
|
||||
WEAK_ALIAS void TAMPER_Handler(void);
|
||||
WEAK_ALIAS void GPIOP0_Handler(void);
|
||||
WEAK_ALIAS void GPIOP1_Handler(void);
|
||||
WEAK_ALIAS void GPIOP2_Handler(void);
|
||||
WEAK_ALIAS void GPIOP3_Handler(void);
|
||||
WEAK_ALIAS void GPIOP4_Handler(void);
|
||||
WEAK_ALIAS void GPIOP5_Handler(void);
|
||||
WEAK_ALIAS void GPIOP6_Handler(void);
|
||||
WEAK_ALIAS void GPIOP7_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ0_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ1_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ2_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ3_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ4_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ5_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ6_Handler(void);
|
||||
WEAK_ALIAS void GPIOQ7_Handler(void);
|
||||
WEAK_ALIAS void TIMER6A_Handler(void);
|
||||
WEAK_ALIAS void TIMER6B_Handler(void);
|
||||
WEAK_ALIAS void TIMER7A_Handler(void);
|
||||
WEAK_ALIAS void TIMER7B_Handler(void);
|
||||
WEAK_ALIAS void I2C6_Handler(void);
|
||||
WEAK_ALIAS void I2C7_Handler(void);
|
||||
WEAK_ALIAS void I2C8_Handler(void);
|
||||
WEAK_ALIAS void I2C9_Handler(void);
|
||||
|
||||
extern void _estack();
|
||||
|
||||
// IRQ table
|
||||
__attribute__((section(".vectors"))) void (*tab[16 + 114])(void) = {
|
||||
// Cortex interrupts
|
||||
_estack, Reset_Handler, NMI_Handler, HardFault_Handler, MemManage_Handler,
|
||||
BusFault_Handler, UsageFault_Handler, 0, 0, 0, 0, SVC_Handler,
|
||||
DebugMon_Handler, 0, PendSV_Handler, SysTick_Handler,
|
||||
|
||||
// Interrupts from peripherals
|
||||
GPIOA_Handler, GPIOB_Handler, GPIOC_Handler, GPIOD_Handler, GPIOE_Handler,
|
||||
UART0_Handler, UART1_Handler, SSI0_Handler, I2C0_Handler,
|
||||
PMW0_FAULT_Handler, PWM0_0_Handler, PWM0_1_Handler, PWM0_2_Handler,
|
||||
QEI0_Handler, ADC0SS0_Handler, ADC0SS1_Handler, ADC0SS2_Handler,
|
||||
ADC0SS3_Handler, WDT0_Handler, TIMER0A_Handler, TIMER0B_Handler,
|
||||
TIMER1A_Handler, TIMER1B_Handler, TIMER2A_Handler, TIMER2B_Handler,
|
||||
COMP0_Handler, COMP1_Handler, COMP2_Handler, SYSCTL_Handler, FLASH_Handler,
|
||||
GPIOF_Handler, GPIOG_Handler, GPIOH_Handler, UART2_Handler, SSI1_Handler,
|
||||
TIMER3A_Handler, TIMER3B_Handler, I2C1_Handler, CAN0_Handler, CAN1_Handler,
|
||||
EMAC0_IRQHandler, HIB_Handler, USB0_Handler, PWM0_3_Handler, UDMA_Handler,
|
||||
UDMAERR_Handler, ADC1SS0_Handler, ADC1SS1_Handler, ADC1SS2_Handler,
|
||||
ADC1SS3_Handler, EPI0_Handler, GPIOJ_Handler, GPIOK_Handler, GPIOL_Handler,
|
||||
SSI2_Handler, SSI3_Handler, UART3_Handler, UART4_Handler, UART5_Handler,
|
||||
UART6_Handler, UART7_Handler, I2C2_Handler, I2C3_Handler, TIMER4A_Handler,
|
||||
TIMER4B_Handler, TIMER5A_Handler, TIMER5B_Handler, FPU_Handler, 0, 0,
|
||||
I2C4_Handler, I2C5_Handler, GPIOM_Handler, GPION_Handler, 0, TAMPER_Handler,
|
||||
GPIOP0_Handler, GPIOP1_Handler, GPIOP2_Handler, GPIOP3_Handler,
|
||||
GPIOP4_Handler, GPIOP5_Handler, GPIOP6_Handler, GPIOP7_Handler,
|
||||
GPIOQ0_Handler, GPIOQ1_Handler, GPIOQ2_Handler, GPIOQ3_Handler,
|
||||
GPIOQ4_Handler, GPIOQ5_Handler, GPIOQ6_Handler, GPIOQ7_Handler, 0, 0, 0, 0,
|
||||
0, 0, TIMER6A_Handler, TIMER6B_Handler, TIMER7A_Handler, TIMER7B_Handler,
|
||||
I2C6_Handler, I2C7_Handler, 0, 0, 0, 0, 0, I2C8_Handler, I2C9_Handler, 0, 0,
|
||||
0};
|
88
examples/ti/ek-tm4c1294xl-rndis/syscalls.c
Normal file
88
examples/ti/ek-tm4c1294xl-rndis/syscalls.c
Normal file
@ -0,0 +1,88 @@
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
int _fstat(int fd, struct stat *st) {
|
||||
if (fd < 0) return -1;
|
||||
st->st_mode = S_IFCHR;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void *_sbrk(int incr) {
|
||||
extern char _end;
|
||||
static unsigned char *heap = NULL;
|
||||
unsigned char *prev_heap;
|
||||
unsigned char x = 0, *heap_end = (unsigned char *)((size_t) &x - 512);
|
||||
(void) x;
|
||||
if (heap == NULL) heap = (unsigned char *) &_end;
|
||||
prev_heap = heap;
|
||||
if (heap + incr > heap_end) return (void *) -1;
|
||||
heap += incr;
|
||||
return prev_heap;
|
||||
}
|
||||
|
||||
int _open(const char *path) {
|
||||
(void) path;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _close(int fd) {
|
||||
(void) fd;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _isatty(int fd) {
|
||||
(void) fd;
|
||||
return 1;
|
||||
}
|
||||
|
||||
int _lseek(int fd, int ptr, int dir) {
|
||||
(void) fd, (void) ptr, (void) dir;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void _exit(int status) {
|
||||
(void) status;
|
||||
for (;;) asm volatile("BKPT #0");
|
||||
}
|
||||
|
||||
void _kill(int pid, int sig) {
|
||||
(void) pid, (void) sig;
|
||||
}
|
||||
|
||||
int _getpid(void) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _write(int fd, char *ptr, int len) {
|
||||
(void) fd, (void) ptr, (void) len;
|
||||
if (fd == 1) uart_write_buf(UART_DEBUG, ptr, (size_t) len);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _read(int fd, char *ptr, int len) {
|
||||
(void) fd, (void) ptr, (void) len;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _link(const char *a, const char *b) {
|
||||
(void) a, (void) b;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _unlink(const char *a) {
|
||||
(void) a;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _stat(const char *path, struct stat *st) {
|
||||
(void) path, (void) st;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int mkdir(const char *path, mode_t mode) {
|
||||
(void) path, (void) mode;
|
||||
return -1;
|
||||
}
|
||||
|
||||
void _init(void) {}
|
36
examples/ti/ek-tm4c1294xl-rndis/sysinit.c
Normal file
36
examples/ti/ek-tm4c1294xl-rndis/sysinit.c
Normal file
@ -0,0 +1,36 @@
|
||||
// Copyright (c) 2023 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
//
|
||||
// This file contains essentials required by the CMSIS:
|
||||
// uint32_t SystemCoreClock - holds the system core clock value
|
||||
// SystemInit() - initialises the system, e.g. sets up clocks
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
uint32_t SystemCoreClock = SYS_FREQUENCY;
|
||||
|
||||
void SystemInit(void) { // Called automatically by startup code
|
||||
SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); // Enable FPU
|
||||
asm("DSB");
|
||||
asm("ISB");
|
||||
SETBITS(SYSCTL->MOSCCTL, BIT(3) | BIT(2),
|
||||
BIT(4)); // Enable MOSC circuit (clear NOXTAL and PWRDN, set >10MHz
|
||||
// range)
|
||||
SETBITS(SYSCTL->MEMTIM0,
|
||||
BIT(21) | BIT(5) | 0x1F << 21 | 0xF << 16 | 0x1F << 5 | 0xF << 0,
|
||||
FLASH_CLKHIGH << 22 | FLASH_WAITST << 16 | FLASH_CLKHIGH << 5 |
|
||||
FLASH_WAITST << 0); // Configure flash timing (not yet applied)
|
||||
SETBITS(SYSCTL->RSCLKCFG, 0xF << 24 | (BIT(9) - 1),
|
||||
3 << 24); // Clear PLL divider, set MOSC as PLL source
|
||||
SYSCTL->PLLFREQ1 = (PLL_Q - 1) << 8 | (PLL_N - 1)
|
||||
<< 0; // Set PLL_Q and PLL_N
|
||||
SYSCTL->PLLFREQ0 =
|
||||
BIT(23) | PLL_M << 0; // Set PLL_Q, power up PLL (if it were on, we'd
|
||||
// need to set NEWFREQ in RSCLKCFG instead)
|
||||
while ((SYSCTL->PLLSTAT & BIT(0)) == 0) spin(1); // Wait for lock
|
||||
SYSCTL->RSCLKCFG |=
|
||||
BIT(31) | BIT(28) |
|
||||
(PSYSDIV - 1) << 0; // Update memory timing, use PLL, set clock divisor
|
||||
|
||||
SysTick_Config(SystemCoreClock / 1000); // Sys tick every 1ms
|
||||
}
|
14
examples/ti/ek-tm4c1294xl-rndis/tinyusb.patch
Normal file
14
examples/ti/ek-tm4c1294xl-rndis/tinyusb.patch
Normal file
@ -0,0 +1,14 @@
|
||||
diff --git a/src/portable/mentor/musb/musb_tm4c.h b/src/portable/mentor/musb/musb_tm4c.h
|
||||
index 65a1751..fb17bdb 100644
|
||||
--- a/src/portable/mentor/musb/musb_tm4c.h
|
||||
+++ b/src/portable/mentor/musb/musb_tm4c.h
|
||||
@@ -33,7 +33,8 @@
|
||||
|
||||
#if CFG_TUSB_MCU == OPT_MCU_TM4C123
|
||||
#include "TM4C123.h"
|
||||
-//#elif CFG_TUSB_MCU == OPT_MCU_TM4C129
|
||||
+#elif CFG_TUSB_MCU == OPT_MCU_TM4C129
|
||||
+ #include "TM4C129.h"
|
||||
#else
|
||||
#error "Unsupported MCUs"
|
||||
#endif
|
10
examples/ti/ek-tm4c1294xl-rndis/tusb_config.h
Normal file
10
examples/ti/ek-tm4c1294xl-rndis/tusb_config.h
Normal file
@ -0,0 +1,10 @@
|
||||
#pragma once
|
||||
|
||||
#define TUD_OPT_RHPORT 0
|
||||
#define CFG_TUSB_MCU OPT_MCU_TM4C129
|
||||
#define CFG_TUSB_OS OPT_OS_NONE
|
||||
#define CFG_TUSB_DEBUG 0
|
||||
#define CFG_TUH_ENABLED 0
|
||||
#define CFG_TUD_ENABLED 1
|
||||
#define CFG_TUD_ENDPOINT0_SIZE 64
|
||||
#define CFG_TUD_ECM_RNDIS 1
|
248
examples/ti/ek-tm4c1294xl-rndis/usb_descriptors.c
Normal file
248
examples/ti/ek-tm4c1294xl-rndis/usb_descriptors.c
Normal file
@ -0,0 +1,248 @@
|
||||
/*
|
||||
* 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.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "tusb.h"
|
||||
|
||||
/* A combination of interfaces must have a unique product id, since PC will save device driver after the first plug.
|
||||
* Same VID/PID with different interface e.g MSC (first), then CDC (later) will possibly cause system error on PC.
|
||||
*
|
||||
* Auto ProductID layout's Bitmap:
|
||||
* [MSB] NET | VENDOR | MIDI | HID | MSC | CDC [LSB]
|
||||
*/
|
||||
#define _PID_MAP(itf, n) ( (CFG_TUD_##itf) << (n) )
|
||||
#define USB_PID (0x4000 | _PID_MAP(CDC, 0) | _PID_MAP(MSC, 1) | _PID_MAP(HID, 2) | \
|
||||
_PID_MAP(MIDI, 3) | _PID_MAP(VENDOR, 4) | _PID_MAP(ECM_RNDIS, 5) | _PID_MAP(NCM, 5) )
|
||||
|
||||
// String Descriptor Index
|
||||
enum
|
||||
{
|
||||
STRID_LANGID = 0,
|
||||
STRID_MANUFACTURER,
|
||||
STRID_PRODUCT,
|
||||
STRID_SERIAL,
|
||||
STRID_INTERFACE,
|
||||
STRID_MAC
|
||||
};
|
||||
|
||||
enum
|
||||
{
|
||||
ITF_NUM_CDC = 0,
|
||||
ITF_NUM_CDC_DATA,
|
||||
ITF_NUM_TOTAL
|
||||
};
|
||||
|
||||
enum
|
||||
{
|
||||
#if CFG_TUD_ECM_RNDIS
|
||||
CONFIG_ID_RNDIS = 0,
|
||||
CONFIG_ID_ECM = 1,
|
||||
#else
|
||||
CONFIG_ID_NCM = 0,
|
||||
#endif
|
||||
CONFIG_ID_COUNT
|
||||
};
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Device Descriptors
|
||||
//--------------------------------------------------------------------+
|
||||
tusb_desc_device_t const desc_device =
|
||||
{
|
||||
.bLength = sizeof(tusb_desc_device_t),
|
||||
.bDescriptorType = TUSB_DESC_DEVICE,
|
||||
.bcdUSB = 0x0200,
|
||||
|
||||
// Use Interface Association Descriptor (IAD) device class
|
||||
.bDeviceClass = TUSB_CLASS_MISC,
|
||||
.bDeviceSubClass = MISC_SUBCLASS_COMMON,
|
||||
.bDeviceProtocol = MISC_PROTOCOL_IAD,
|
||||
|
||||
.bMaxPacketSize0 = CFG_TUD_ENDPOINT0_SIZE,
|
||||
|
||||
.idVendor = 0xCafe,
|
||||
.idProduct = USB_PID,
|
||||
.bcdDevice = 0x0101,
|
||||
|
||||
.iManufacturer = STRID_MANUFACTURER,
|
||||
.iProduct = STRID_PRODUCT,
|
||||
.iSerialNumber = STRID_SERIAL,
|
||||
|
||||
.bNumConfigurations = CONFIG_ID_COUNT // multiple configurations
|
||||
};
|
||||
|
||||
// Invoked when received GET DEVICE DESCRIPTOR
|
||||
// Application return pointer to descriptor
|
||||
uint8_t const * tud_descriptor_device_cb(void)
|
||||
{
|
||||
return (uint8_t const *) &desc_device;
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Configuration Descriptor
|
||||
//--------------------------------------------------------------------+
|
||||
#define MAIN_CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + TUD_RNDIS_DESC_LEN)
|
||||
#define ALT_CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_ECM_DESC_LEN)
|
||||
#define NCM_CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_NCM_DESC_LEN)
|
||||
|
||||
#if CFG_TUSB_MCU == OPT_MCU_LPC175X_6X || CFG_TUSB_MCU == OPT_MCU_LPC177X_8X || CFG_TUSB_MCU == OPT_MCU_LPC40XX
|
||||
// LPC 17xx and 40xx endpoint type (bulk/interrupt/iso) are fixed by its number
|
||||
// 0 control, 1 In, 2 Bulk, 3 Iso, 4 In etc ...
|
||||
#define EPNUM_NET_NOTIF 0x81
|
||||
#define EPNUM_NET_OUT 0x02
|
||||
#define EPNUM_NET_IN 0x82
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_SAMG || CFG_TUSB_MCU == OPT_MCU_SAMX7X
|
||||
// SAMG & SAME70 don't support a same endpoint number with different direction IN and OUT
|
||||
// e.g EP1 OUT & EP1 IN cannot exist together
|
||||
#define EPNUM_NET_NOTIF 0x81
|
||||
#define EPNUM_NET_OUT 0x02
|
||||
#define EPNUM_NET_IN 0x83
|
||||
|
||||
#else
|
||||
#define EPNUM_NET_NOTIF 0x81
|
||||
#define EPNUM_NET_OUT 0x02
|
||||
#define EPNUM_NET_IN 0x82
|
||||
#endif
|
||||
|
||||
#if CFG_TUD_ECM_RNDIS
|
||||
|
||||
static uint8_t const rndis_configuration[] =
|
||||
{
|
||||
// Config number (index+1), interface count, string index, total length, attribute, power in mA
|
||||
TUD_CONFIG_DESCRIPTOR(CONFIG_ID_RNDIS+1, ITF_NUM_TOTAL, 0, MAIN_CONFIG_TOTAL_LEN, 0, 100),
|
||||
|
||||
// Interface number, string index, EP notification address and size, EP data address (out, in) and size.
|
||||
TUD_RNDIS_DESCRIPTOR(ITF_NUM_CDC, STRID_INTERFACE, EPNUM_NET_NOTIF, 8, EPNUM_NET_OUT, EPNUM_NET_IN, CFG_TUD_NET_ENDPOINT_SIZE),
|
||||
};
|
||||
|
||||
static uint8_t const ecm_configuration[] =
|
||||
{
|
||||
// Config number (index+1), interface count, string index, total length, attribute, power in mA
|
||||
TUD_CONFIG_DESCRIPTOR(CONFIG_ID_ECM+1, ITF_NUM_TOTAL, 0, ALT_CONFIG_TOTAL_LEN, 0, 100),
|
||||
|
||||
// Interface number, description string index, MAC address string index, EP notification address and size, EP data address (out, in), and size, max segment size.
|
||||
TUD_CDC_ECM_DESCRIPTOR(ITF_NUM_CDC, STRID_INTERFACE, STRID_MAC, EPNUM_NET_NOTIF, 64, EPNUM_NET_OUT, EPNUM_NET_IN, CFG_TUD_NET_ENDPOINT_SIZE, CFG_TUD_NET_MTU),
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
static uint8_t const ncm_configuration[] =
|
||||
{
|
||||
// Config number (index+1), interface count, string index, total length, attribute, power in mA
|
||||
TUD_CONFIG_DESCRIPTOR(CONFIG_ID_NCM+1, ITF_NUM_TOTAL, 0, NCM_CONFIG_TOTAL_LEN, 0, 100),
|
||||
|
||||
// Interface number, description string index, MAC address string index, EP notification address and size, EP data address (out, in), and size, max segment size.
|
||||
TUD_CDC_NCM_DESCRIPTOR(ITF_NUM_CDC, STRID_INTERFACE, STRID_MAC, EPNUM_NET_NOTIF, 64, EPNUM_NET_OUT, EPNUM_NET_IN, CFG_TUD_NET_ENDPOINT_SIZE, CFG_TUD_NET_MTU),
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
// Configuration array: RNDIS and CDC-ECM
|
||||
// - Windows only works with RNDIS
|
||||
// - MacOS only works with CDC-ECM
|
||||
// - Linux will work on both
|
||||
static uint8_t const * const configuration_arr[2] =
|
||||
{
|
||||
#if CFG_TUD_ECM_RNDIS
|
||||
[CONFIG_ID_RNDIS] = rndis_configuration,
|
||||
[CONFIG_ID_ECM ] = ecm_configuration
|
||||
#else
|
||||
[CONFIG_ID_NCM ] = ncm_configuration
|
||||
#endif
|
||||
};
|
||||
|
||||
// Invoked when received GET CONFIGURATION DESCRIPTOR
|
||||
// Application return pointer to descriptor
|
||||
// Descriptor contents must exist long enough for transfer to complete
|
||||
uint8_t const * tud_descriptor_configuration_cb(uint8_t index)
|
||||
{
|
||||
return (index < CONFIG_ID_COUNT) ? configuration_arr[index] : NULL;
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// String Descriptors
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// array of pointer to string descriptors
|
||||
static char const* string_desc_arr [] =
|
||||
{
|
||||
[STRID_LANGID] = (const char[]) { 0x09, 0x04 }, // supported language is English (0x0409)
|
||||
[STRID_MANUFACTURER] = "TinyUSB", // Manufacturer
|
||||
[STRID_PRODUCT] = "TinyUSB Device", // Product
|
||||
[STRID_SERIAL] = "123456", // Serial
|
||||
[STRID_INTERFACE] = "TinyUSB Network Interface" // Interface Description
|
||||
|
||||
// STRID_MAC index is handled separately
|
||||
};
|
||||
|
||||
static uint16_t _desc_str[32];
|
||||
|
||||
// Invoked when received GET STRING DESCRIPTOR request
|
||||
// Application return pointer to descriptor, whose contents must exist long enough for transfer to complete
|
||||
uint16_t const* tud_descriptor_string_cb(uint8_t index, uint16_t langid)
|
||||
{
|
||||
(void) langid;
|
||||
|
||||
unsigned int chr_count = 0;
|
||||
|
||||
if (STRID_LANGID == index)
|
||||
{
|
||||
memcpy(&_desc_str[1], string_desc_arr[STRID_LANGID], 2);
|
||||
chr_count = 1;
|
||||
}
|
||||
else if (STRID_MAC == index)
|
||||
{
|
||||
// Convert MAC address into UTF-16
|
||||
|
||||
for (unsigned i=0; i<sizeof(tud_network_mac_address); i++)
|
||||
{
|
||||
_desc_str[1+chr_count++] = "0123456789ABCDEF"[(tud_network_mac_address[i] >> 4) & 0xf];
|
||||
_desc_str[1+chr_count++] = "0123456789ABCDEF"[(tud_network_mac_address[i] >> 0) & 0xf];
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Note: the 0xEE index string is a Microsoft OS 1.0 Descriptors.
|
||||
// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/microsoft-defined-usb-descriptors
|
||||
|
||||
if ( !(index < sizeof(string_desc_arr)/sizeof(string_desc_arr[0])) ) return NULL;
|
||||
|
||||
const char* str = string_desc_arr[index];
|
||||
|
||||
// Cap at max char
|
||||
chr_count = (uint8_t) strlen(str);
|
||||
if ( chr_count > (TU_ARRAY_SIZE(_desc_str) - 1)) chr_count = TU_ARRAY_SIZE(_desc_str) - 1;
|
||||
|
||||
// Convert ASCII string into UTF-16
|
||||
for (unsigned int i=0; i<chr_count; i++)
|
||||
{
|
||||
_desc_str[1+i] = str[i];
|
||||
}
|
||||
}
|
||||
|
||||
// first byte is length (including header), second byte is string type
|
||||
_desc_str[0] = (uint16_t) ((TUSB_DESC_STRING << 8 ) | (2*chr_count + 2));
|
||||
|
||||
return _desc_str;
|
||||
}
|
Loading…
Reference in New Issue
Block a user