Browse Source

Adding initial Teensy 3 support, compiles, but not fully functional yet.

- CDC Output seems to be working
- USB Keyboard output has not been tested, but is "ready"
- UART and Timers have not been tested, or fully utilized
- Issues using Timer 0
- Initial template for MBC-55X Scan module (only module currently compatible with the arm build)
- Updated the interface to the AVR usb module for symmetry with the ARM usb module
- Much gutting was done to the Teensy 3 usb keyboard module, though not in an ideal state yet
simple
Jacob Alexander 11 years ago
parent
commit
c8b4baf652

+ 2
- 2
CMakeLists.txt View File

@@ -27,8 +27,8 @@ include( AddFileDependencies )
#| "avr" # Teensy++ 1.0
#| "avr" # Teensy++ 2.0
#| "arm" # Teensy 3.0
#set( COMPILER_FAMILY "arm" )
set( COMPILER_FAMILY "avr" )
set( COMPILER_FAMILY "arm" )
#set( COMPILER_FAMILY "avr" )

message( STATUS "Compiler Family:" )
message( "${COMPILER_FAMILY}" )

+ 4
- 0
Debug/print/print.h View File

@@ -50,7 +50,11 @@
*/

// Function Aliases
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
#define dPrint(c) usb_debug_putchar(c)
#elif defined(_mk20dx128_) // ARM
#define dPrint(c) usb_debug_putstr (c)
#endif
#define dPrintStr(c) usb_debug_putstr (c)
#define dPrintStrs(...) usb_debug_putstrs(__VA_ARGS__, "\0\0\0") // Convenience Variadic Macro
#define dPrintStrNL(c) dPrintStrs (c, NL) // Appends New Line Macro

+ 63
- 0
Lib/Interrupts.h View File

@@ -0,0 +1,63 @@
/* Copyright (C) 2013 by Jacob Alexander
*
* 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 include file unifies some of the nomenclature between the AVR and ARM compilers


// ----- Includes -----

#ifndef __INTERRUPTS_H
#define __INTERRUPTS_H

// ARM
#if defined(_mk20dx128_)

#include <Lib/mk20dx128.h>

// AVR
#elif defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_)

#include <avr/interrupt.h>

#endif



// ----- Defines -----

// ARM
#if defined(_mk20dx128_)

// Map the Interrupt Enable/Disable to the AVR names
#define cli() __disable_irq()
#define sei() __enable_irq()


// AVR
#elif defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_)


#endif


#endif


+ 37
- 0
Lib/aliased_bitband.h View File

@@ -0,0 +1,37 @@

#ifndef __aliased_bitband_h
#define __aliased_bitband_h


// Aliased Regions for single bit (0th) register access

// Chapter 4: Memory Map (Table 4-1)



// TODO
// - Not all tested, and not all sections added



// 0x2200 0000 - 0x23FF FFFF - Aliased to SRAM_U bitband
// TODO



// 0x4200 0000 - 0x43FF FFFF - Aliased to AIPS and GPIO bitband
#define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000)
#define GPIO_BITBAND_PTR(reg, bit) ((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)))

// XXX - Only MODREG is tested to work...
#define GPIO_BITBAND_OUTREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 0)
#define GPIO_BITBAND_SETREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 32)
#define GPIO_BITBAND_CLRREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 64)
#define GPIO_BITBAND_TOGREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 96)
#define GPIO_BITBAND_INPREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 128)
#define GPIO_BITBAND_MODREG(reg, bit) *((uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)) + 160)



#endif


+ 37
- 0
Lib/delay.c View File

@@ -0,0 +1,37 @@

#include "delay.h"
#include "mk20dx128.h"

// the systick interrupt is supposed to increment this at 1 kHz rate
volatile uint32_t systick_millis_count = 0;

void yield(void) {};

uint32_t micros(void)
{
uint32_t count, current, istatus;

__disable_irq();
current = SYST_CVR;
count = systick_millis_count;
istatus = SCB_ICSR; // bit 26 indicates if systick exception pending
__enable_irq();
if ((istatus & SCB_ICSR_PENDSTSET) && current > ((F_CPU / 1000) - 50)) count++;
current = ((F_CPU / 1000) - 1) - current;
return count * 1000 + current / (F_CPU / 1000000);
}

void delay(uint32_t ms)
{
uint32_t start = micros();

while (1) {
if ((micros() - start) >= 1000) {
ms--;
if (ms == 0) break;
start += 1000;
}
yield();
}
}


+ 48
- 0
Lib/delay.h View File

@@ -0,0 +1,48 @@

#ifndef __DELAY_H
#define __DELAY_H

#include <stdint.h>

// Convenience Macros, for delay compatibility with AVR-GCC
#define _delay_ms(val) delay( val )
#define _delay_us(val) delayMicroseconds( val )


// the systick interrupt is supposed to increment this at 1 kHz rate
extern volatile uint32_t systick_millis_count;

static inline uint32_t millis(void) __attribute__((always_inline, unused));
static inline uint32_t millis(void)
{
return systick_millis_count; // single aligned 32 bit is atomic;
}


static inline void delayMicroseconds(uint32_t) __attribute__((always_inline, unused));
static inline void delayMicroseconds(uint32_t usec)
{
#if F_CPU == 96000000
uint32_t n = usec << 5;
#elif F_CPU == 48000000
uint32_t n = usec << 4;
#elif F_CPU == 24000000
uint32_t n = usec << 3;
#endif
asm volatile(
"L_%=_delayMicroseconds:" "\n\t"
"subs %0, #1" "\n\t"
"bne L_%=_delayMicroseconds" "\n"
: "+r" (n) :
);
}


void yield(void) __attribute__ ((weak));

uint32_t micros(void);

void delay(uint32_t ms);

#endif


+ 328
- 0
Lib/mk20dx128.c View File

@@ -0,0 +1,328 @@
#include "mk20dx128.h"


extern unsigned long _stext;
extern unsigned long _etext;
extern unsigned long _sdata;
extern unsigned long _edata;
extern unsigned long _sbss;
extern unsigned long _ebss;
extern unsigned long _estack;
//extern void __init_array_start(void);
//extern void __init_array_end(void);
extern int main (void);
void ResetHandler(void);
void _init_Teensyduino_internal_(void);
void __libc_init_array(void);


void fault_isr(void)
{
while (1); // die
}

void unused_isr(void)
{
while (1); // die
}

extern volatile uint32_t systick_millis_count;
void systick_default_isr(void)
{
systick_millis_count++;
}

void nmi_isr(void) __attribute__ ((weak, alias("unused_isr")));
void hard_fault_isr(void) __attribute__ ((weak, alias("unused_isr")));
void memmanage_fault_isr(void) __attribute__ ((weak, alias("unused_isr")));
void bus_fault_isr(void) __attribute__ ((weak, alias("unused_isr")));
void usage_fault_isr(void) __attribute__ ((weak, alias("unused_isr")));
void svcall_isr(void) __attribute__ ((weak, alias("unused_isr")));
void debugmonitor_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pendablesrvreq_isr(void) __attribute__ ((weak, alias("unused_isr")));
void systick_isr(void) __attribute__ ((weak, alias("systick_default_isr")));

void dma_ch0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void dma_ch1_isr(void) __attribute__ ((weak, alias("unused_isr")));
void dma_ch2_isr(void) __attribute__ ((weak, alias("unused_isr")));
void dma_ch3_isr(void) __attribute__ ((weak, alias("unused_isr")));
void dma_error_isr(void) __attribute__ ((weak, alias("unused_isr")));
void flash_cmd_isr(void) __attribute__ ((weak, alias("unused_isr")));
void flash_error_isr(void) __attribute__ ((weak, alias("unused_isr")));
void low_voltage_isr(void) __attribute__ ((weak, alias("unused_isr")));
void wakeup_isr(void) __attribute__ ((weak, alias("unused_isr")));
void watchdog_isr(void) __attribute__ ((weak, alias("unused_isr")));
void i2c0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void spi0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void i2s0_tx_isr(void) __attribute__ ((weak, alias("unused_isr")));
void i2s0_rx_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart0_lon_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart0_status_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart0_error_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart1_status_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart1_error_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart2_status_isr(void) __attribute__ ((weak, alias("unused_isr")));
void uart2_error_isr(void) __attribute__ ((weak, alias("unused_isr")));
void adc0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void cmp0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void cmp1_isr(void) __attribute__ ((weak, alias("unused_isr")));
void ftm0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void ftm1_isr(void) __attribute__ ((weak, alias("unused_isr")));
void cmt_isr(void) __attribute__ ((weak, alias("unused_isr")));
void rtc_alarm_isr(void) __attribute__ ((weak, alias("unused_isr")));
void rtc_seconds_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pit0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pit1_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pit2_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pit3_isr(void) __attribute__ ((weak, alias("unused_isr")));
void pdb_isr(void) __attribute__ ((weak, alias("unused_isr")));
void usb_isr(void) __attribute__ ((weak, alias("unused_isr")));
void usb_charge_isr(void) __attribute__ ((weak, alias("unused_isr")));
void tsi0_isr(void) __attribute__ ((weak, alias("unused_isr")));
void mcg_isr(void) __attribute__ ((weak, alias("unused_isr")));
void lptmr_isr(void) __attribute__ ((weak, alias("unused_isr")));
void porta_isr(void) __attribute__ ((weak, alias("unused_isr")));
void portb_isr(void) __attribute__ ((weak, alias("unused_isr")));
void portc_isr(void) __attribute__ ((weak, alias("unused_isr")));
void portd_isr(void) __attribute__ ((weak, alias("unused_isr")));
void porte_isr(void) __attribute__ ((weak, alias("unused_isr")));
void software_isr(void) __attribute__ ((weak, alias("unused_isr")));


// TODO: create AVR-stype ISR() macro, with default linkage to undefined handler
//
__attribute__ ((section(".vectors"), used))
void (* const gVectors[])(void) =
{
(void (*)(void))((unsigned long)&_estack), // 0 ARM: Initial Stack Pointer
ResetHandler, // 1 ARM: Initial Program Counter
nmi_isr, // 2 ARM: Non-maskable Interrupt (NMI)
hard_fault_isr, // 3 ARM: Hard Fault
memmanage_fault_isr, // 4 ARM: MemManage Fault
bus_fault_isr, // 5 ARM: Bus Fault
usage_fault_isr, // 6 ARM: Usage Fault
fault_isr, // 7 --
fault_isr, // 8 --
fault_isr, // 9 --
fault_isr, // 10 --
svcall_isr, // 11 ARM: Supervisor call (SVCall)
debugmonitor_isr, // 12 ARM: Debug Monitor
fault_isr, // 13 --
pendablesrvreq_isr, // 14 ARM: Pendable req serv(PendableSrvReq)
systick_isr, // 15 ARM: System tick timer (SysTick)
dma_ch0_isr, // 16 DMA channel 0 transfer complete
dma_ch1_isr, // 17 DMA channel 1 transfer complete
dma_ch2_isr, // 18 DMA channel 2 transfer complete
dma_ch3_isr, // 19 DMA channel 3 transfer complete
dma_error_isr, // 20 DMA error interrupt channel
unused_isr, // 21 DMA --
flash_cmd_isr, // 22 Flash Memory Command complete
flash_error_isr, // 23 Flash Read collision
low_voltage_isr, // 24 Low-voltage detect/warning
wakeup_isr, // 25 Low Leakage Wakeup
watchdog_isr, // 26 Both EWM and WDOG interrupt
i2c0_isr, // 27 I2C0
spi0_isr, // 28 SPI0
i2s0_tx_isr, // 29 I2S0 Transmit
i2s0_rx_isr, // 30 I2S0 Receive
uart0_lon_isr, // 31 UART0 CEA709.1-B (LON) status
uart0_status_isr, // 32 UART0 status
uart0_error_isr, // 33 UART0 error
uart1_status_isr, // 34 UART1 status
uart1_error_isr, // 35 UART1 error
uart2_status_isr, // 36 UART2 status
uart2_error_isr, // 37 UART2 error
adc0_isr, // 38 ADC0
cmp0_isr, // 39 CMP0
cmp1_isr, // 40 CMP1
ftm0_isr, // 41 FTM0
ftm1_isr, // 42 FTM1
cmt_isr, // 43 CMT
rtc_alarm_isr, // 44 RTC Alarm interrupt
rtc_seconds_isr, // 45 RTC Seconds interrupt
pit0_isr, // 46 PIT Channel 0
pit1_isr, // 47 PIT Channel 1
pit2_isr, // 48 PIT Channel 2
pit3_isr, // 49 PIT Channel 3
pdb_isr, // 50 PDB Programmable Delay Block
usb_isr, // 51 USB OTG
usb_charge_isr, // 52 USB Charger Detect
tsi0_isr, // 53 TSI0
mcg_isr, // 54 MCG
lptmr_isr, // 55 Low Power Timer
porta_isr, // 56 Pin detect (Port A)
portb_isr, // 57 Pin detect (Port B)
portc_isr, // 58 Pin detect (Port C)
portd_isr, // 59 Pin detect (Port D)
porte_isr, // 60 Pin detect (Port E)
software_isr, // 61 Software interrupt
};

//void usb_isr(void)
//{
//}

__attribute__ ((section(".flashconfig"), used))
const uint8_t flashconfigbytes[16] = {
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF
};


// Automatically initialize the RTC. When the build defines the compile
// time, and the user has added a crystal, the RTC will automatically
// begin at the time of the first upload.
#ifndef TIME_T
#define TIME_T 1349049600 // default 1 Oct 2012
#endif
extern void rtc_set(unsigned long t);



void startup_unused_hook(void) {}
void startup_early_hook(void) __attribute__ ((weak, alias("startup_unused_hook")));
void startup_late_hook(void) __attribute__ ((weak, alias("startup_unused_hook")));


__attribute__ ((section(".startup")))
void ResetHandler(void)
{
uint32_t *src = &_etext;
uint32_t *dest = &_sdata;

WDOG_UNLOCK = WDOG_UNLOCK_SEQ1;
WDOG_UNLOCK = WDOG_UNLOCK_SEQ2;
WDOG_STCTRLH = WDOG_STCTRLH_ALLOWUPDATE;
startup_early_hook();

// enable clocks to always-used peripherals
SIM_SCGC5 = 0x00043F82; // clocks active to all GPIO
SIM_SCGC6 = SIM_SCGC6_RTC | SIM_SCGC6_FTM0 | SIM_SCGC6_FTM1 | SIM_SCGC6_ADC0 | SIM_SCGC6_FTFL;
// if the RTC oscillator isn't enabled, get it started early
if (!(RTC_CR & RTC_CR_OSCE)) {
RTC_SR = 0;
RTC_CR = RTC_CR_SC16P | RTC_CR_SC4P | RTC_CR_OSCE;
}

// TODO: do this while the PLL is waiting to lock....
while (dest < &_edata) *dest++ = *src++;
dest = &_sbss;
while (dest < &_ebss) *dest++ = 0;
SCB_VTOR = 0; // use vector table in flash

// start in FEI mode
// enable capacitors for crystal
OSC0_CR = OSC_SC8P | OSC_SC2P;
// enable osc, 8-32 MHz range, low power mode
MCG_C2 = MCG_C2_RANGE0(2) | MCG_C2_EREFS;
// switch to crystal as clock source, FLL input = 16 MHz / 512
MCG_C1 = MCG_C1_CLKS(2) | MCG_C1_FRDIV(4);
// wait for crystal oscillator to begin
while ((MCG_S & MCG_S_OSCINIT0) == 0) ;
// wait for FLL to use oscillator
while ((MCG_S & MCG_S_IREFST) != 0) ;
// wait for MCGOUT to use oscillator
while ((MCG_S & MCG_S_CLKST_MASK) != MCG_S_CLKST(2)) ;
// now we're in FBE mode
// config PLL input for 16 MHz Crystal / 4 = 4 MHz
MCG_C5 = MCG_C5_PRDIV0(3);
// config PLL for 96 MHz output
MCG_C6 = MCG_C6_PLLS | MCG_C6_VDIV0(0);
// wait for PLL to start using xtal as its input
while (!(MCG_S & MCG_S_PLLST)) ;
// wait for PLL to lock
while (!(MCG_S & MCG_S_LOCK0)) ;
// now we're in PBE mode
#if F_CPU == 96000000
// config divisors: 96 MHz core, 48 MHz bus, 24 MHz flash
SIM_CLKDIV1 = SIM_CLKDIV1_OUTDIV1(0) | SIM_CLKDIV1_OUTDIV2(1) | SIM_CLKDIV1_OUTDIV4(3);
#elif F_CPU == 48000000
// config divisors: 48 MHz core, 48 MHz bus, 24 MHz flash
SIM_CLKDIV1 = SIM_CLKDIV1_OUTDIV1(1) | SIM_CLKDIV1_OUTDIV2(1) | SIM_CLKDIV1_OUTDIV4(3);
#elif F_CPU == 24000000
// config divisors: 24 MHz core, 24 MHz bus, 24 MHz flash
SIM_CLKDIV1 = SIM_CLKDIV1_OUTDIV1(3) | SIM_CLKDIV1_OUTDIV2(3) | SIM_CLKDIV1_OUTDIV4(3);
#else
#error "Error, F_CPU must be 96000000, 48000000, or 24000000"
#endif
// switch to PLL as clock source, FLL input = 16 MHz / 512
MCG_C1 = MCG_C1_CLKS(0) | MCG_C1_FRDIV(4);
// wait for PLL clock to be used
while ((MCG_S & MCG_S_CLKST_MASK) != MCG_S_CLKST(3)) ;
// now we're in PEE mode
// configure USB for 48 MHz clock
SIM_CLKDIV2 = SIM_CLKDIV2_USBDIV(1); // USB = 96 MHz PLL / 2
// USB uses PLL clock, trace is CPU clock, CLKOUT=OSCERCLK0
SIM_SOPT2 = SIM_SOPT2_USBSRC | SIM_SOPT2_PLLFLLSEL | SIM_SOPT2_TRACECLKSEL | SIM_SOPT2_CLKOUTSEL(6);

// initialize the SysTick counter
SYST_RVR = (F_CPU / 1000) - 1;
SYST_CSR = SYST_CSR_CLKSOURCE | SYST_CSR_TICKINT | SYST_CSR_ENABLE;

//init_pins();
__enable_irq();

//_init_Teensyduino_internal_(); XXX HaaTa - Why is this here? Perhaps fixed in a new version of the API?
//if (RTC_SR & RTC_SR_TIF) rtc_set(TIME_T); XXX HaaTa - We don't care about the rtc

__libc_init_array();

/*
for (ptr = &__init_array_start; ptr < &__init_array_end; ptr++) {
(*ptr)();
}
*/
startup_late_hook();
main();
while (1) ;
}

// TODO: is this needed for c++ and where does it come from?
/*
void _init(void)
{
}
*/


void * _sbrk(int incr)
{
static char *heap_end = (char *)&_ebss;
char *prev = heap_end;

heap_end += incr;
return prev;
}

int _read(int file, char *ptr, int len)
{
return 0;
}

int _write(int file, char *ptr, int len)
{
return 0;
}

int _close(int fd)
{
return -1;
}

int _lseek(int fd, long long offset, int whence)
{
return -1;
}

void _exit(int status)
{
while (1);
}

void __cxa_pure_virtual()
{
while (1);
}




+ 1486
- 0
Lib/mk20dx128.h
File diff suppressed because it is too large
View File


+ 73
- 0
Lib/mk20dx128.ld View File

@@ -0,0 +1,73 @@
MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 128K
RAM (rwx) : ORIGIN = 0x1FFFE000, LENGTH = 16K
}


SECTIONS
{
.text : {
. = 0;
KEEP(*(.vectors))
*(.startup*)
/* TODO: does linker detect startup overflow onto flashconfig? */
. = 0x400;
KEEP(*(.flashconfig*))
*(.text*)
*(.rodata*)
. = ALIGN(4);
KEEP(*(.init))
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
} > FLASH = 0xFF

.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > FLASH
_etext = .;

.usbdescriptortable (NOLOAD) : {
/* . = ORIGIN(RAM); */
. = ALIGN(512);
*(.usbdescriptortable*)
} > RAM

.usbbuffers (NOLOAD) : {
. = ALIGN(4);
*(.usbbuffers*)
} > RAM

.data : AT (_etext) {
. = ALIGN(4);
_sdata = .;
*(.data*)
. = ALIGN(4);
_edata = .;
} > RAM

.noinit (NOLOAD) : {
*(.noinit*)
} > RAM

.bss : {
. = ALIGN(4);
_sbss = .;
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .;
} > RAM

_estack = ORIGIN(RAM) + LENGTH(RAM);
}



+ 46
- 0
Lib/pin_map.teensy3 View File

@@ -0,0 +1,46 @@
// Pin Arduino
// 0 B16 RXD
// 1 B17 TXD
// 2 D0
// 3 A12 FTM1_CH0
// 4 A13 FTM1_CH1
// 5 D7 FTM0_CH7 OC0B/T1
// 6 D4 FTM0_CH4 OC0A
// 7 D2
// 8 D3 ICP1
// 9 C3 FTM0_CH2 OC1A
// 10 C4 FTM0_CH3 SS/OC1B
// 11 C6 MOSI/OC2A
// 12 C7 MISO
// 13 C5 SCK
// 14 D1
// 15 C0
// 16 B0 (FTM1_CH0)
// 17 B1 (FTM1_CH1)
// 18 B3 SDA
// 19 B2 SCL
// 20 D5 FTM0_CH5
// 21 D6 FTM0_CH6
// 22 C1 FTM0_CH0
// 23 C2 FTM0_CH1
// 24 A5 (FTM0_CH2)
// 25 B19
// 26 E1
// 27 C9
// 28 C8
// 29 C10
// 30 C11
// 31 E0
// 32 B18
// 33 A4 (FTM0_CH1)
// (34) analog only
// (35) analog only
// (36) analog only
// (37) analog only

// not available to user:
// A0 FTM0_CH5 SWD Clock
// A1 FTM0_CH6 USB ID
// A2 FTM0_CH7 SWD Trace
// A3 FTM0_CH0 SWD Data


+ 236
- 0
Scan/MBC-55X/scan_loop.c View File

@@ -0,0 +1,236 @@
/* Copyright (C) 2013 by Jacob Alexander
*
* 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.
*/

// ----- Includes -----

// Compiler Includes
#include <Lib/ScanLib.h>

// Project Includes
#include <led.h>
#include <print.h>

// Local Includes
#include "scan_loop.h"



// ----- Defines -----


// ----- Macros -----

// Make sure we haven't overflowed the buffer
#define bufferAdd(byte) \
if ( KeyIndex_BufferUsed < KEYBOARD_BUFFER ) \
KeyIndex_Buffer[KeyIndex_BufferUsed++] = byte



// ----- Variables -----

// Buffer used to inform the macro processing module which keys have been detected as pressed
volatile uint8_t KeyIndex_Buffer[KEYBOARD_BUFFER];
volatile uint8_t KeyIndex_BufferUsed;



// ----- Function Declarations -----

void processKeyValue( uint8_t valueType );
void removeKeyValue( uint8_t keyValue );



// ----- Interrupt Functions -----

// UART Receive Buffer Full Interrupt
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
ISR(USART1_RX_vect)
#elif defined(_mk20dx128_) // ARM
void uart0_status_isr(void)
#endif
{
cli(); // Disable Interrupts

// Read part of the scan code (3 8bit chunks) from USART
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
uint8_t tmp = UDR1;
#elif defined(_mk20dx128_) // ARM
// TODO
uint8_t tmp = 0;
#endif

// Debug
char tmpStr[6];
hexToStr( tmp, tmpStr );
dPrintStrs( tmpStr, " " ); // Debug

// TODO

sei(); // Re-enable Interrupts
}



// ----- Functions -----

// Setup
inline void scan_setup()
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
{
// Setup the the USART interface for keyboard data input

// TODO
// Setup baud rate
// 16 MHz / ( 16 * Baud ) = UBRR
// Baud: 4817 -> 16 MHz / ( 16 * 4817 ) = 207.5981
// Thus baud setting = 208
uint16_t baud = 208; // Max setting of 4095
UBRR1H = (uint8_t)(baud >> 8);
UBRR1L = (uint8_t)baud;

// Enable the receiver, transmitter, and RX Complete Interrupt
UCSR1B = 0x98;

// Set frame format: 8 data, 1 stop bit, odd parity
// Asynchrounous USART mode
UCSR1C = 0x36;

// Reset the keyboard before scanning, we might be in a wierd state
scan_resetKeyboard();
}
#elif defined(_mk20dx128_) // ARM
{
// Setup the the UART interface for keyboard data input

// Setup baud rate
// TODO

// Reset the keyboard before scanning, we might be in a wierd state
scan_resetKeyboard();
}
#endif


// Main Detection Loop
inline uint8_t scan_loop()
{
return 0;
}

void processKeyValue( uint8_t keyValue )
{
// TODO Process ASCII

// Make sure the key isn't already in the buffer
for ( uint8_t c = 0; c < KeyIndex_BufferUsed + 1; c++ )
{
// Key isn't in the buffer yet
if ( c == KeyIndex_BufferUsed )
{
bufferAdd( keyValue );
break;
}

// Key already in the buffer
if ( KeyIndex_Buffer[c] == keyValue )
break;
}
}

void removeKeyValue( uint8_t keyValue )
{
// Check for the released key, and shift the other keys lower on the buffer
uint8_t c;
for ( c = 0; c < KeyIndex_BufferUsed; c++ )
{
// Key to release found
if ( KeyIndex_Buffer[c] == keyValue )
{
// Shift keys from c position
for ( uint8_t k = c; k < KeyIndex_BufferUsed - 1; k++ )
KeyIndex_Buffer[k] = KeyIndex_Buffer[k + 1];

// Decrement Buffer
KeyIndex_BufferUsed--;

break;
}
}

// Error case (no key to release)
if ( c == KeyIndex_BufferUsed + 1 )
{
errorLED( 1 );
char tmpStr[6];
hexToStr( keyValue, tmpStr );
erro_dPrint( "Could not find key to release: ", tmpStr );
}
}

// Send data
uint8_t scan_sendData( uint8_t dataPayload )
{
// Debug
char tmpStr[6];
hexToStr( dataPayload, tmpStr );
info_dPrint( "Sending - ", tmpStr );

#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
UDR1 = dataPayload;
#elif defined(_mk20dx128_) // ARM
// TODO
#endif

return 0;
}

// Signal KeyIndex_Buffer that it has been properly read
void scan_finishedWithBuffer( uint8_t sentKeys )
{
}

// Signal that the keys have been properly sent over USB
void scan_finishedWithUSBBuffer( uint8_t sentKeys )
{
}

// Reset/Hold keyboard
// NOTE: Does nothing with the FACOM6684
void scan_lockKeyboard( void )
{
}

// NOTE: Does nothing with the FACOM6684
void scan_unlockKeyboard( void )
{
}

// Reset Keyboard
void scan_resetKeyboard( void )
{
// Not a calculated valued...
_delay_ms( 50 );

KeyIndex_BufferUsed = 0;
}


+ 67
- 0
Scan/MBC-55X/scan_loop.h View File

@@ -0,0 +1,67 @@
/* Copyright (C) 2013 by Jacob Alexander
*
* 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.
*/

#ifndef __SCAN_LOOP_H
#define __SCAN_LOOP_H

// ----- Includes -----

// Compiler Includes
#include <stdint.h>

// Local Includes



// ----- Defines -----

#define KEYBOARD_KEYS 0x7F // 127 - Size of the array space for the keyboard(max index)
#define KEYBOARD_BUFFER 24 // Max number of key signals to buffer



// ----- Variables -----

extern volatile uint8_t KeyIndex_Buffer[KEYBOARD_BUFFER];
extern volatile uint8_t KeyIndex_BufferUsed;
extern volatile uint8_t KeyIndex_Add_InputSignal;



// ----- Functions -----

// Functions used by main.c
void scan_setup( void );
uint8_t scan_loop( void );


// Functions available to macro.c
uint8_t scan_sendData( uint8_t dataPayload );

void scan_finishedWithBuffer( uint8_t sentKeys );
void scan_finishedWithUSBBuffer( uint8_t sentKeys );
void scan_lockKeyboard( void );
void scan_unlockKeyboard( void );
void scan_resetKeyboard( void );


#endif // __SCAN_LOOP_H


+ 48
- 0
Scan/MBC-55X/setup.cmake View File

@@ -0,0 +1,48 @@
###| CMake Kiibohd Controller Scan Module |###
#
# Written by Jacob Alexander in 2013 for the Kiibohd Controller
#
# Released into the Public Domain
#
# For the Sanyo MBC-55X Series of keyboards
#
###


###
# Module C files
#

set( SCAN_SRCS
scan_loop.c
)


###
# Module H files
#
set( SCAN_HDRS
scan_loop.h
)


###
# File Dependency Setup
#
ADD_FILE_DEPENDENCIES( scan_loop.c ${SCAN_HDRS} )
#add_file_dependencies( scan_loop.c ${SCAN_HDRS} )
#add_file_dependencies( macro.c keymap.h facom6684.h )


###
# Module Specific Options
#
add_definitions( -I${HEAD_DIR}/Keymap )

#| Keymap Settings
add_definitions(
-DMODIFIER_MASK=facom6684_ModifierMask
#-DKEYINDEX_MASK=facom6684_ColemakMap
-DKEYINDEX_MASK=facom6684_DefaultMap
)


+ 556
- 0
USB/pjrc/arm/usb_desc.c View File

@@ -0,0 +1,556 @@
#include "usb_desc.h"


// USB Descriptors are binary data which the USB host reads to
// automatically detect a USB device's capabilities. The format
// and meaning of every field is documented in numerous USB
// standards. When working with USB descriptors, despite the
// complexity of the standards and poor writing quality in many
// of those documents, remember descriptors are nothing more
// than constant binary data that tells the USB host what the
// device can do. Computers will load drivers based on this data.
// Those drivers then communicate on the endpoints specified by
// the descriptors.

// To configure a new combination of interfaces or make minor
// changes to existing configuration (eg, change the name or ID
// numbers), usually you would edit "usb_desc.h". This file
// is meant to be configured by the header, so generally it is
// only edited to add completely new USB interfaces or features.



// **************************************************************
// USB Device
// **************************************************************

#define LSB(n) ((n) & 255)
#define MSB(n) (((n) >> 8) & 255)

// USB Device Descriptor. The USB host reads this first, to learn
// what type of device is connected.
static uint8_t device_descriptor[] = {
18, // bLength
1, // bDescriptorType
0x00, 0x02, // bcdUSB
#ifdef DEVICE_CLASS
DEVICE_CLASS, // bDeviceClass
#else
0,
#endif
#ifdef DEVICE_SUBCLASS
DEVICE_SUBCLASS, // bDeviceSubClass
#else
0,
#endif
#ifdef DEVICE_PROTOCOL
DEVICE_PROTOCOL, // bDeviceProtocol
#else
0,
#endif
EP0_SIZE, // bMaxPacketSize0
LSB(VENDOR_ID), MSB(VENDOR_ID), // idVendor
LSB(PRODUCT_ID), MSB(PRODUCT_ID), // idProduct
0x00, 0x01, // bcdDevice
1, // iManufacturer
2, // iProduct
3, // iSerialNumber
1 // bNumConfigurations
};

// These descriptors must NOT be "const", because the USB DMA
// has trouble accessing flash memory with enough bandwidth
// while the processor is executing from flash.



// **************************************************************
// HID Report Descriptors
// **************************************************************

// Each HID interface needs a special report descriptor that tells
// the meaning and format of the data.

#ifdef KEYBOARD_INTERFACE
// Keyboard Protocol 1, HID 1.11 spec, Appendix B, page 59-60
static uint8_t keyboard_report_desc[] = {
0x05, 0x01, // Usage Page (Generic Desktop),
0x09, 0x06, // Usage (Keyboard),
0xA1, 0x01, // Collection (Application),
0x75, 0x01, // Report Size (1),
0x95, 0x08, // Report Count (8),
0x05, 0x07, // Usage Page (Key Codes),
0x19, 0xE0, // Usage Minimum (224),
0x29, 0xE7, // Usage Maximum (231),
0x15, 0x00, // Logical Minimum (0),
0x25, 0x01, // Logical Maximum (1),
0x81, 0x02, // Input (Data, Variable, Absolute), ;Modifier byte
0x95, 0x08, // Report Count (8),
0x75, 0x01, // Report Size (1),
0x15, 0x00, // Logical Minimum (0),
0x25, 0x01, // Logical Maximum (1),
0x05, 0x0C, // Usage Page (Consumer),
0x09, 0xE9, // Usage (Volume Increment),
0x09, 0xEA, // Usage (Volume Decrement),
0x09, 0xE2, // Usage (Mute),
0x09, 0xCD, // Usage (Play/Pause),
0x09, 0xB5, // Usage (Scan Next Track),
0x09, 0xB6, // Usage (Scan Previous Track),
0x09, 0xB7, // Usage (Stop),
0x09, 0xB8, // Usage (Eject),
0x81, 0x02, // Input (Data, Variable, Absolute), ;Media keys
0x95, 0x05, // Report Count (5),
0x75, 0x01, // Report Size (1),
0x05, 0x08, // Usage Page (LEDs),
0x19, 0x01, // Usage Minimum (1),
0x29, 0x05, // Usage Maximum (5),
0x91, 0x02, // Output (Data, Variable, Absolute), ;LED report
0x95, 0x01, // Report Count (1),
0x75, 0x03, // Report Size (3),
0x91, 0x03, // Output (Constant), ;LED report padding
0x95, 0x06, // Report Count (6),
0x75, 0x08, // Report Size (8),
0x15, 0x00, // Logical Minimum (0),
0x25, 0x7F, // Logical Maximum(104),
0x05, 0x07, // Usage Page (Key Codes),
0x19, 0x00, // Usage Minimum (0),
0x29, 0x7F, // Usage Maximum (104),
0x81, 0x00, // Input (Data, Array), ;Normal keys
0xc0 // End Collection
};
#endif

#ifdef MOUSE_INTERFACE
// Mouse Protocol 1, HID 1.11 spec, Appendix B, page 59-60, with wheel extension
static uint8_t mouse_report_desc[] = {
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x02, // Usage (Mouse)
0xA1, 0x01, // Collection (Application)
0x05, 0x09, // Usage Page (Button)
0x19, 0x01, // Usage Minimum (Button #1)
0x29, 0x03, // Usage Maximum (Button #3)
0x15, 0x00, // Logical Minimum (0)
0x25, 0x01, // Logical Maximum (1)
0x95, 0x03, // Report Count (3)
0x75, 0x01, // Report Size (1)
0x81, 0x02, // Input (Data, Variable, Absolute)
0x95, 0x01, // Report Count (1)
0x75, 0x05, // Report Size (5)
0x81, 0x03, // Input (Constant)
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x30, // Usage (X)
0x09, 0x31, // Usage (Y)
0x15, 0x81, // Logical Minimum (-127)
0x25, 0x7F, // Logical Maximum (127)
0x75, 0x08, // Report Size (8),
0x95, 0x02, // Report Count (2),
0x81, 0x06, // Input (Data, Variable, Relative)
0x09, 0x38, // Usage (Wheel)
0x95, 0x01, // Report Count (1),
0x81, 0x06, // Input (Data, Variable, Relative)
0xC0 // End Collection
};
#endif

#ifdef JOYSTICK_INTERFACE
static uint8_t joystick_report_desc[] = {
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x04, // Usage (Joystick)
0xA1, 0x01, // Collection (Application)
0x15, 0x00, // Logical Minimum (0)
0x25, 0x01, // Logical Maximum (1)
0x75, 0x01, // Report Size (1)
0x95, 0x20, // Report Count (32)
0x05, 0x09, // Usage Page (Button)
0x19, 0x01, // Usage Minimum (Button #1)
0x29, 0x20, // Usage Maximum (Button #32)
0x81, 0x02, // Input (variable,absolute)
0x15, 0x00, // Logical Minimum (0)
0x25, 0x07, // Logical Maximum (7)
0x35, 0x00, // Physical Minimum (0)
0x46, 0x3B, 0x01, // Physical Maximum (315)
0x75, 0x04, // Report Size (4)
0x95, 0x01, // Report Count (1)
0x65, 0x14, // Unit (20)
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x39, // Usage (Hat switch)
0x81, 0x42, // Input (variable,absolute,null_state)
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x01, // Usage (Pointer)
0xA1, 0x00, // Collection ()
0x15, 0x00, // Logical Minimum (0)
0x26, 0xFF, 0x03, // Logical Maximum (1023)
0x75, 0x0A, // Report Size (10)
0x95, 0x04, // Report Count (4)
0x09, 0x30, // Usage (X)
0x09, 0x31, // Usage (Y)
0x09, 0x32, // Usage (Z)
0x09, 0x35, // Usage (Rz)
0x81, 0x02, // Input (variable,absolute)
0xC0, // End Collection
0x15, 0x00, // Logical Minimum (0)
0x26, 0xFF, 0x03, // Logical Maximum (1023)
0x75, 0x0A, // Report Size (10)
0x95, 0x02, // Report Count (2)
0x09, 0x36, // Usage (Slider)
0x09, 0x36, // Usage (Slider)
0x81, 0x02, // Input (variable,absolute)
0xC0 // End Collection
};
#endif



// **************************************************************
// USB Configuration
// **************************************************************

// USB Configuration Descriptor. This huge descriptor tells all
// of the devices capbilities.
static uint8_t config_descriptor[CONFIG_DESC_SIZE] = {
// configuration descriptor, USB spec 9.6.3, page 264-266, Table 9-10
9, // bLength;
2, // bDescriptorType;
LSB(CONFIG_DESC_SIZE), // wTotalLength
MSB(CONFIG_DESC_SIZE),
NUM_INTERFACE, // bNumInterfaces
1, // bConfigurationValue
0, // iConfiguration
0xC0, // bmAttributes
50, // bMaxPower

#ifdef CDC_IAD_DESCRIPTOR
// interface association descriptor, USB ECN, Table 9-Z
8, // bLength
11, // bDescriptorType
CDC_STATUS_INTERFACE, // bFirstInterface
2, // bInterfaceCount
0x02, // bFunctionClass
0x02, // bFunctionSubClass
0x01, // bFunctionProtocol
4, // iFunction
#endif

#ifdef CDC_DATA_INTERFACE
// interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
9, // bLength
4, // bDescriptorType
CDC_STATUS_INTERFACE, // bInterfaceNumber
0, // bAlternateSetting
1, // bNumEndpoints
0x02, // bInterfaceClass
0x02, // bInterfaceSubClass
0x01, // bInterfaceProtocol
0, // iInterface
// CDC Header Functional Descriptor, CDC Spec 5.2.3.1, Table 26
5, // bFunctionLength
0x24, // bDescriptorType
0x00, // bDescriptorSubtype
0x10, 0x01, // bcdCDC
// Call Management Functional Descriptor, CDC Spec 5.2.3.2, Table 27
5, // bFunctionLength
0x24, // bDescriptorType
0x01, // bDescriptorSubtype
0x01, // bmCapabilities
1, // bDataInterface
// Abstract Control Management Functional Descriptor, CDC Spec 5.2.3.3, Table 28
4, // bFunctionLength
0x24, // bDescriptorType
0x02, // bDescriptorSubtype
0x06, // bmCapabilities
// Union Functional Descriptor, CDC Spec 5.2.3.8, Table 33
5, // bFunctionLength
0x24, // bDescriptorType
0x06, // bDescriptorSubtype
CDC_STATUS_INTERFACE, // bMasterInterface
CDC_DATA_INTERFACE, // bSlaveInterface0
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
CDC_ACM_ENDPOINT | 0x80, // bEndpointAddress
0x03, // bmAttributes (0x03=intr)
CDC_ACM_SIZE, 0, // wMaxPacketSize
64, // bInterval
// interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
9, // bLength
4, // bDescriptorType
CDC_DATA_INTERFACE, // bInterfaceNumber
0, // bAlternateSetting
2, // bNumEndpoints
0x0A, // bInterfaceClass
0x00, // bInterfaceSubClass
0x00, // bInterfaceProtocol
0, // iInterface
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
CDC_RX_ENDPOINT, // bEndpointAddress
0x02, // bmAttributes (0x02=bulk)
CDC_RX_SIZE, 0, // wMaxPacketSize
0, // bInterval
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
CDC_TX_ENDPOINT | 0x80, // bEndpointAddress
0x02, // bmAttributes (0x02=bulk)
CDC_TX_SIZE, 0, // wMaxPacketSize
0, // bInterval
#endif // CDC_DATA_INTERFACE

#ifdef KEYBOARD_INTERFACE
// interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
9, // bLength
4, // bDescriptorType
KEYBOARD_INTERFACE, // bInterfaceNumber
0, // bAlternateSetting
1, // bNumEndpoints
0x03, // bInterfaceClass (0x03 = HID)
0x01, // bInterfaceSubClass (0x01 = Boot)
0x01, // bInterfaceProtocol (0x01 = Keyboard)
0, // iInterface
// HID interface descriptor, HID 1.11 spec, section 6.2.1
9, // bLength
0x21, // bDescriptorType
0x11, 0x01, // bcdHID
0, // bCountryCode
1, // bNumDescriptors
0x22, // bDescriptorType
LSB(sizeof(keyboard_report_desc)), // wDescriptorLength
MSB(sizeof(keyboard_report_desc)),
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
KEYBOARD_ENDPOINT | 0x80, // bEndpointAddress
0x03, // bmAttributes (0x03=intr)
KEYBOARD_SIZE, 0, // wMaxPacketSize
KEYBOARD_INTERVAL, // bInterval
#endif // KEYBOARD_INTERFACE

#ifdef MOUSE_INTERFACE
// interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
9, // bLength
4, // bDescriptorType
MOUSE_INTERFACE, // bInterfaceNumber
0, // bAlternateSetting
1, // bNumEndpoints
0x03, // bInterfaceClass (0x03 = HID)
0x01, // bInterfaceSubClass (0x01 = Boot)
0x02, // bInterfaceProtocol (0x02 = Mouse)
0, // iInterface
// HID interface descriptor, HID 1.11 spec, section 6.2.1
9, // bLength
0x21, // bDescriptorType
0x11, 0x01, // bcdHID
0, // bCountryCode
1, // bNumDescriptors
0x22, // bDescriptorType
LSB(sizeof(mouse_report_desc)), // wDescriptorLength
MSB(sizeof(mouse_report_desc)),
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
MOUSE_ENDPOINT | 0x80, // bEndpointAddress
0x03, // bmAttributes (0x03=intr)
MOUSE_SIZE, 0, // wMaxPacketSize
MOUSE_INTERVAL, // bInterval
#endif // MOUSE_INTERFACE

#ifdef JOYSTICK_INTERFACE
// interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
9, // bLength
4, // bDescriptorType
JOYSTICK_INTERFACE, // bInterfaceNumber
0, // bAlternateSetting
1, // bNumEndpoints
0x03, // bInterfaceClass (0x03 = HID)
0x00, // bInterfaceSubClass
0x00, // bInterfaceProtocol
0, // iInterface
// HID interface descriptor, HID 1.11 spec, section 6.2.1
9, // bLength
0x21, // bDescriptorType
0x11, 0x01, // bcdHID
0, // bCountryCode
1, // bNumDescriptors
0x22, // bDescriptorType
LSB(sizeof(joystick_report_desc)), // wDescriptorLength
MSB(sizeof(joystick_report_desc)),
// endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
7, // bLength
5, // bDescriptorType
JOYSTICK_ENDPOINT | 0x80, // bEndpointAddress
0x03, // bmAttributes (0x03=intr)
JOYSTICK_SIZE, 0, // wMaxPacketSize
JOYSTICK_INTERVAL, // bInterval
#endif
};



// **************************************************************
// String Descriptors
// **************************************************************

// The descriptors above can provide human readable strings,
// referenced by index numbers. These descriptors are the
// actual string data

struct usb_string_descriptor_struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wString[];
};

static struct usb_string_descriptor_struct string0 = {
4,
3,
{0x0409}
};

static struct usb_string_descriptor_struct string1 = {
2 + MANUFACTURER_NAME_LEN * 2,
3,
MANUFACTURER_NAME
};
static struct usb_string_descriptor_struct string2 = {
2 + PRODUCT_NAME_LEN * 2,
3,
PRODUCT_NAME
};
static struct usb_string_descriptor_struct string3 = {
12,
3,
{'1','2','3','4','5'}
};


// **************************************************************
// Descriptors List
// **************************************************************

// This table provides access to all the descriptor data above.

const usb_descriptor_list_t usb_descriptor_list[] = {
//wValue, wIndex, address, length
{0x0100, 0x0000, device_descriptor, sizeof(device_descriptor)},
{0x0200, 0x0000, config_descriptor, sizeof(config_descriptor)},
#ifdef KEYBOARD_INTERFACE
{0x2200, KEYBOARD_INTERFACE, keyboard_report_desc, sizeof(keyboard_report_desc)},
{0x2100, KEYBOARD_INTERFACE, config_descriptor+KEYBOARD_DESC_OFFSET, 9},
#endif
#ifdef MOUSE_INTERFACE
{0x2200, MOUSE_INTERFACE, mouse_report_desc, sizeof(mouse_report_desc)},
{0x2100, MOUSE_INTERFACE, config_descriptor+MOUSE_DESC_OFFSET, 9},
#endif
#ifdef JOYSTICK_INTERFACE
{0x2200, JOYSTICK_INTERFACE, joystick_report_desc, sizeof(joystick_report_desc)},
{0x2100, JOYSTICK_INTERFACE, config_descriptor+JOYSTICK_DESC_OFFSET, 9},
#endif
{0x0300, 0x0000, (const uint8_t *)&string0, 4},
{0x0301, 0x0409, (const uint8_t *)&string1, 2 + MANUFACTURER_NAME_LEN * 2},
{0x0302, 0x0409, (const uint8_t *)&string2, 2 + PRODUCT_NAME_LEN * 2},
{0x0303, 0x0409, (const uint8_t *)&string3, 12},
{0, 0, NULL, 0}
};


// **************************************************************
// Endpoint Configuration
// **************************************************************

#if 0
// 0x00 = not used
// 0x19 = Recieve only
// 0x15 = Transmit only
// 0x1D = Transmit & Recieve
//
const uint8_t usb_endpoint_config_table[NUM_ENDPOINTS] =
{
0x00, 0x15, 0x19, 0x15, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
#endif


const uint8_t usb_endpoint_config_table[NUM_ENDPOINTS] =
{
#if (defined(ENDPOINT1_CONFIG) && NUM_ENDPOINTS >= 1)
ENDPOINT1_CONFIG,
#elif (NUM_ENDPOINTS >= 1)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT2_CONFIG) && NUM_ENDPOINTS >= 2)
ENDPOINT2_CONFIG,
#elif (NUM_ENDPOINTS >= 2)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT3_CONFIG) && NUM_ENDPOINTS >= 3)
ENDPOINT3_CONFIG,
#elif (NUM_ENDPOINTS >= 3)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT4_CONFIG) && NUM_ENDPOINTS >= 4)
ENDPOINT4_CONFIG,
#elif (NUM_ENDPOINTS >= 4)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT5_CONFIG) && NUM_ENDPOINTS >= 5)
ENDPOINT5_CONFIG,
#elif (NUM_ENDPOINTS >= 5)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT6_CONFIG) && NUM_ENDPOINTS >= 6)
ENDPOINT6_CONFIG,
#elif (NUM_ENDPOINTS >= 6)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT7_CONFIG) && NUM_ENDPOINTS >= 7)
ENDPOINT7_CONFIG,
#elif (NUM_ENDPOINTS >= 7)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT8_CONFIG) && NUM_ENDPOINTS >= 8)
ENDPOINT8_CONFIG,
#elif (NUM_ENDPOINTS >= 8)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT9_CONFIG) && NUM_ENDPOINTS >= 9)
ENDPOINT9_CONFIG,
#elif (NUM_ENDPOINTS >= 9)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT10_CONFIG) && NUM_ENDPOINTS >= 10)
ENDPOINT10_CONFIG,
#elif (NUM_ENDPOINTS >= 10)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT11_CONFIG) && NUM_ENDPOINTS >= 11)
ENDPOINT11_CONFIG,
#elif (NUM_ENDPOINTS >= 11)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT12_CONFIG) && NUM_ENDPOINTS >= 12)
ENDPOINT12_CONFIG,
#elif (NUM_ENDPOINTS >= 12)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT13_CONFIG) && NUM_ENDPOINTS >= 13)
ENDPOINT13_CONFIG,
#elif (NUM_ENDPOINTS >= 13)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT14_CONFIG) && NUM_ENDPOINTS >= 14)
ENDPOINT14_CONFIG,
#elif (NUM_ENDPOINTS >= 14)
ENDPOINT_UNUSED,
#endif
#if (defined(ENDPOINT15_CONFIG) && NUM_ENDPOINTS >= 15)
ENDPOINT15_CONFIG,
#elif (NUM_ENDPOINTS >= 15)
ENDPOINT_UNUSED,
#endif
};





+ 80
- 0
USB/pjrc/arm/usb_desc.h View File

@@ -0,0 +1,80 @@
#ifndef _usb_desc_h_
#define _usb_desc_h_

// This header is NOT meant to be included when compiling
// user sketches in Arduino. The low-level functions
// provided by usb_dev.c are meant to be called only by
// code which provides higher-level interfaces to the user.

#include <stdint.h>
#include <stddef.h>
#include "usb_com.h"

#define ENDPOINT_UNUSED 0x00
#define ENDPOINT_TRANSIMIT_ONLY 0x15
#define ENDPOINT_RECEIVE_ONLY 0x19
#define ENDPOINT_TRANSMIT_AND_RECEIVE 0x1D

// Some operating systems, especially Windows, may cache USB device
// info. Changes to the device name may not update on the same
// computer unless the vendor or product ID numbers change, or the
// "bcdDevice" revision code is increased.

#define DEVICE_CLASS 0xEF
#define DEVICE_SUBCLASS 0x02
#define DEVICE_PROTOCOL 0x01
#define MANUFACTURER_NAME {'T','e','e','n','s','y','d','u','i','n','o'}
#define MANUFACTURER_NAME_LEN 11
#define PRODUCT_NAME {'S','e','r','i','a','l','/','K','e','y','b','o','a','r','d','/','M','o','u','s','e','/','J','o','y','s','t','i','c','k'}
#define PRODUCT_NAME_LEN 30
#define EP0_SIZE 64
#define NUM_ENDPOINTS 15
#define NUM_INTERFACE 5
#define CDC_IAD_DESCRIPTOR 1
#define CDC_STATUS_INTERFACE 0
#define CDC_DATA_INTERFACE 1 // Serial
#define CDC_ACM_ENDPOINT 2
#define CDC_RX_ENDPOINT 3
#define CDC_TX_ENDPOINT 4
#define CDC_ACM_SIZE 16
#define CDC_RX_SIZE 64
#define CDC_TX_SIZE 64
#define KEYBOARD_INTERFACE 2 // Keyboard
#define KEYBOARD_ENDPOINT 1
#define KEYBOARD_SIZE 8
#define KEYBOARD_INTERVAL 1
#define MOUSE_INTERFACE 3 // Mouse
#define MOUSE_ENDPOINT 5
#define MOUSE_SIZE 8
#define MOUSE_INTERVAL 2
#define JOYSTICK_INTERFACE 4 // Joystick
#define JOYSTICK_ENDPOINT 6
#define JOYSTICK_SIZE 16
#define JOYSTICK_INTERVAL 1
#define KEYBOARD_DESC_OFFSET (9+8 + 9+5+5+4+5+7+9+7+7 + 9)
#define MOUSE_DESC_OFFSET (9+8 + 9+5+5+4+5+7+9+7+7 + 9+9+7 + 9)
#define JOYSTICK_DESC_OFFSET (9+8 + 9+5+5+4+5+7+9+7+7 + 9+9+7 + 9+9+7 + 9)
#define CONFIG_DESC_SIZE (9+8 + 9+5+5+4+5+7+9+7+7 + 9+9+7 + 9+9+7 + 9+9+7)
#define ENDPOINT1_CONFIG ENDPOINT_TRANSIMIT_ONLY
#define ENDPOINT2_CONFIG ENDPOINT_TRANSIMIT_ONLY
#define ENDPOINT3_CONFIG ENDPOINT_RECEIVE_ONLY
#define ENDPOINT4_CONFIG ENDPOINT_TRANSIMIT_ONLY
#define ENDPOINT5_CONFIG ENDPOINT_TRANSIMIT_ONLY
#define ENDPOINT6_CONFIG ENDPOINT_TRANSIMIT_ONLY



// NUM_ENDPOINTS = number of non-zero endpoints (0 to 15)
extern const uint8_t usb_endpoint_config_table[NUM_ENDPOINTS];

typedef struct {
uint16_t wValue;
uint16_t wIndex;
const uint8_t *addr;
uint16_t length;
} usb_descriptor_list_t;

extern const usb_descriptor_list_t usb_descriptor_list[];


#endif

+ 867
- 0
USB/pjrc/arm/usb_dev.c View File

@@ -0,0 +1,867 @@
#include <Lib/USBLib.h>
#include "usb_dev.h"
#include "usb_mem.h"

// buffer descriptor table

typedef struct {
uint32_t desc;
void * addr;
} bdt_t;

__attribute__ ((section(".usbdescriptortable"), used))
static bdt_t table[64];

#define BDT_OWN 0x80
#define BDT_DATA1 0x40
#define BDT_DATA0 0x00
#define BDT_DTS 0x08
#define BDT_STALL 0x04
#define BDT_PID(n) (((n) >> 2) & 15)

#define BDT_DESC(count, data) (BDT_OWN | BDT_DTS \
| ((data) ? BDT_DATA1 : BDT_DATA0) \
| ((count) << 16))

#define TX 1
#define RX 0
#define ODD 1
#define EVEN 0
#define DATA0 0
#define DATA1 1
#define index(endpoint, tx, odd) (((endpoint) << 2) | ((tx) << 1) | (odd))
#define stat2bufferdescriptor(stat) (table + ((stat) >> 2))


static union {
struct {
union {
struct {
uint8_t bmRequestType;
uint8_t bRequest;
};
uint16_t wRequestAndType;
};
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
};
struct {
uint32_t word1;
uint32_t word2;
};
} setup;


#define GET_STATUS 0
#define CLEAR_FEATURE 1
#define SET_FEATURE 3
#define SET_ADDRESS 5
#define GET_DESCRIPTOR 6
#define SET_DESCRIPTOR 7
#define GET_CONFIGURATION 8
#define SET_CONFIGURATION 9
#define GET_INTERFACE 10
#define SET_INTERFACE 11
#define SYNCH_FRAME 12

// SETUP always uses a DATA0 PID for the data field of the SETUP transaction.
// transactions in the data phase start with DATA1 and toggle (figure 8-12, USB1.1)
// Status stage uses a DATA1 PID.

static uint8_t ep0_rx0_buf[EP0_SIZE] __attribute__ ((aligned (4)));
static uint8_t ep0_rx1_buf[EP0_SIZE] __attribute__ ((aligned (4)));
static const uint8_t *ep0_tx_ptr = NULL;
static uint16_t ep0_tx_len;
static uint8_t ep0_tx_bdt_bank = 0;
static uint8_t ep0_tx_data_toggle = 0;
uint8_t usb_rx_memory_needed = 0;

volatile uint8_t usb_configuration = 0;
volatile uint8_t usb_reboot_timer = 0;


static void endpoint0_stall(void)
{
USB0_ENDPT0 = USB_ENDPT_EPSTALL | USB_ENDPT_EPRXEN | USB_ENDPT_EPTXEN | USB_ENDPT_EPHSHK;
}


static void endpoint0_transmit(const void *data, uint32_t len)
{
#if 0
serial_print("tx0:");
serial_phex32((uint32_t)data);
serial_print(",");
serial_phex16(len);
serial_print(ep0_tx_bdt_bank ? ", odd" : ", even");
serial_print(ep0_tx_data_toggle ? ", d1\n" : ", d0\n");
#endif
table[index(0, TX, ep0_tx_bdt_bank)].addr = (void *)data;
table[index(0, TX, ep0_tx_bdt_bank)].desc = BDT_DESC(len, ep0_tx_data_toggle);
ep0_tx_data_toggle ^= 1;
ep0_tx_bdt_bank ^= 1;
}

static uint8_t reply_buffer[8];

static void usbdev_setup(void)
{
const uint8_t *data = NULL;
uint32_t datalen = 0;
const usb_descriptor_list_t *list;
uint32_t size;
volatile uint8_t *reg;
uint8_t epconf;
const uint8_t *cfg;
int i;

switch (setup.wRequestAndType) {
case 0x0500: // SET_ADDRESS
break;
case 0x0900: // SET_CONFIGURATION
//serial_print("configure\n");
usb_configuration = setup.wValue;
reg = &USB0_ENDPT1;
cfg = usb_endpoint_config_table;
// clear all BDT entries, free any allocated memory...
for (i=4; i <= NUM_ENDPOINTS*4; i++) {
if (table[i].desc & BDT_OWN) {
usb_free((usb_packet_t *)((uint8_t *)(table[i].addr) - 8));
table[i].desc = 0;
}
}
usb_rx_memory_needed = 0;
for (i=1; i <= NUM_ENDPOINTS; i++) {
epconf = *cfg++;
*reg = epconf;
reg += 4;
if (epconf & USB_ENDPT_EPRXEN) {
usb_packet_t *p;
p = usb_malloc();
if (p) {
table[index(i, RX, EVEN)].addr = p->buf;
table[index(i, RX, EVEN)].desc = BDT_DESC(64, 0);
} else {
table[index(i, RX, EVEN)].desc = 0;
usb_rx_memory_needed++;
}
p = usb_malloc();
if (p) {
table[index(i, RX, ODD)].addr = p->buf;
table[index(i, RX, ODD)].desc = BDT_DESC(64, 1);
} else {
table[index(i, RX, ODD)].desc = 0;
usb_rx_memory_needed++;
}
}
table[index(i, TX, EVEN)].desc = 0;
table[index(i, TX, ODD)].desc = 0;
}
break;
case 0x0880: // GET_CONFIGURATION
reply_buffer[0] = usb_configuration;
datalen = 1;
data = reply_buffer;
break;
case 0x0080: // GET_STATUS (device)
reply_buffer[0] = 0;
reply_buffer[1] = 0;
datalen = 2;
data = reply_buffer;
break;
case 0x0082: // GET_STATUS (endpoint)
if (setup.wIndex > NUM_ENDPOINTS) {
// TODO: do we need to handle IN vs OUT here?
endpoint0_stall();
return;
}
reply_buffer[0] = 0;
reply_buffer[1] = 0;
if (*(uint8_t *)(&USB0_ENDPT0 + setup.wIndex * 4) & 0x02) reply_buffer[0] = 1;
data = reply_buffer;
datalen = 2;
break;
case 0x0102: // CLEAR_FEATURE (endpoint)
i = setup.wIndex & 0x7F;
if (i > NUM_ENDPOINTS || setup.wValue != 0) {
// TODO: do we need to handle IN vs OUT here?
endpoint0_stall();
return;
}
(*(uint8_t *)(&USB0_ENDPT0 + setup.wIndex * 4)) &= ~0x02;
// TODO: do we need to clear the data toggle here?
break;
case 0x0302: // SET_FEATURE (endpoint)
i = setup.wIndex & 0x7F;
if (i > NUM_ENDPOINTS || setup.wValue != 0) {
// TODO: do we need to handle IN vs OUT here?
endpoint0_stall();
return;
}
(*(uint8_t *)(&USB0_ENDPT0 + setup.wIndex * 4)) |= 0x02;
// TODO: do we need to clear the data toggle here?
break;
case 0x0680: // GET_DESCRIPTOR
case 0x0681:
//serial_print("desc:");
//serial_phex16(setup.wValue);
//serial_print("\n");
for (list = usb_descriptor_list; 1; list++) {
if (list->addr == NULL) break;
//if (setup.wValue == list->wValue &&
//(setup.wIndex == list->wIndex) || ((setup.wValue >> 8) == 3)) {
if (setup.wValue == list->wValue && setup.wIndex == list->wIndex) {
data = list->addr;
datalen = list->length;
#if 0
serial_print("Desc found, ");
serial_phex32((uint32_t)data);
serial_print(",");
serial_phex16(datalen);
serial_print(",");
serial_phex(data[0]);
serial_phex(data[1]);
serial_phex(data[2]);
serial_phex(data[3]);
serial_phex(data[4]);
serial_phex(data[5]);
serial_print("\n");
#endif
goto send;
}
}
//serial_print("desc: not found\n");
endpoint0_stall();
return;
#if defined(CDC_STATUS_INTERFACE)
case 0x2221: // CDC_SET_CONTROL_LINE_STATE
usb_cdc_line_rtsdtr = setup.wValue;
//serial_print("set control line state\n");
break;
case 0x2021: // CDC_SET_LINE_CODING
//serial_print("set coding, waiting...\n");
return;
#endif

// TODO: this does not work... why?
#if defined(SEREMU_INTERFACE) || defined(KEYBOARD_INTERFACE)
case 0x0921: // HID SET_REPORT
//serial_print(":)\n");
return;
case 0x0A21: // HID SET_IDLE
break;
// case 0xC940:
#endif
default:
endpoint0_stall();
return;
}
send:
//serial_print("setup send ");
//serial_phex32(data);
//serial_print(",");
//serial_phex16(datalen);
//serial_print("\n");

if (datalen > setup.wLength) datalen = setup.wLength;
size = datalen;
if (size > EP0_SIZE) size = EP0_SIZE;
endpoint0_transmit(data, size);
data += size;
datalen -= size;
if (datalen == 0 && size < EP0_SIZE) return;

size = datalen;
if (size > EP0_SIZE) size = EP0_SIZE;
endpoint0_transmit(data, size);
data += size;
datalen -= size;
if (datalen == 0 && size < EP0_SIZE) return;

ep0_tx_ptr = data;
ep0_tx_len = datalen;
}



//A bulk endpoint's toggle sequence is initialized to DATA0 when the endpoint
//experiences any configuration event (configuration events are explained in
//Sections 9.1.1.5 and 9.4.5).

//Configuring a device or changing an alternate setting causes all of the status
//and configuration values associated with endpoints in the affected interfaces
//to be set to their default values. This includes setting the data toggle of
//any endpoint using data toggles to the value DATA0.

//For endpoints using data toggle, regardless of whether an endpoint has the
//Halt feature set, a ClearFeature(ENDPOINT_HALT) request always results in the
//data toggle being reinitialized to DATA0.



// #define stat2bufferdescriptor(stat) (table + ((stat) >> 2))

static void usb_control(uint32_t stat)
{
bdt_t *b;
uint32_t pid, size;
uint8_t *buf;
const uint8_t *data;

b = stat2bufferdescriptor(stat);
pid = BDT_PID(b->desc);
//count = b->desc >> 16;
buf = b->addr;
//serial_print("pid:");
//serial_phex(pid);
//serial_print(", count:");
//serial_phex(count);
//serial_print("\n");

switch (pid) {
case 0x0D: // Setup received from host
//serial_print("PID=Setup\n");
//if (count != 8) ; // panic?
// grab the 8 byte setup info
setup.word1 = *(uint32_t *)(buf);
setup.word2 = *(uint32_t *)(buf + 4);

// give the buffer back
b->desc = BDT_DESC(EP0_SIZE, DATA1);
//table[index(0, RX, EVEN)].desc = BDT_DESC(EP0_SIZE, 1);
//table[index(0, RX, ODD)].desc = BDT_DESC(EP0_SIZE, 1);

// clear any leftover pending IN transactions
ep0_tx_ptr = NULL;
if (ep0_tx_data_toggle) {
}
//if (table[index(0, TX, EVEN)].desc & 0x80) {
//serial_print("leftover tx even\n");
//}
//if (table[index(0, TX, ODD)].desc & 0x80) {
//serial_print("leftover tx odd\n");
//}
table[index(0, TX, EVEN)].desc = 0;
table[index(0, TX, ODD)].desc = 0;
// first IN after Setup is always DATA1
ep0_tx_data_toggle = 1;

#if 0
serial_print("bmRequestType:");
serial_phex(setup.bmRequestType);
serial_print(", bRequest:");
serial_phex(setup.bRequest);
serial_print(", wValue:");
serial_phex16(setup.wValue);
serial_print(", wIndex:");
serial_phex16(setup.wIndex);
serial_print(", len:");
serial_phex16(setup.wLength);
serial_print("\n");
#endif
// actually "do" the setup request
usbdev_setup();
// unfreeze the USB, now that we're ready
USB0_CTL = USB_CTL_USBENSOFEN; // clear TXSUSPENDTOKENBUSY bit
break;
case 0x01: // OUT transaction received from host
case 0x02:
//serial_print("PID=OUT\n");
#ifdef CDC_STATUS_INTERFACE
if (setup.wRequestAndType == 0x2021 /*CDC_SET_LINE_CODING*/) {
int i;
uint8_t *dst = usb_cdc_line_coding;
//serial_print("set line coding ");
for (i=0; i<7; i++) {
//serial_phex(*buf);
*dst++ = *buf++;
}
//serial_phex32(*(uint32_t *)usb_cdc_line_coding);
//serial_print("\n");
// TODO - Fix this warning
if (*(uint32_t *)usb_cdc_line_coding == 134) usb_reboot_timer = 15;
endpoint0_transmit(NULL, 0);
}
#endif
#ifdef KEYBOARD_INTERFACE
if (setup.word1 == 0x02000921 && setup.word2 == ((1<<16)|KEYBOARD_INTERFACE)) {
USBKeys_LEDs = buf[0];
endpoint0_transmit(NULL, 0);
}
#endif
// give the buffer back
b->desc = BDT_DESC(EP0_SIZE, DATA1);
break;

case 0x09: // IN transaction completed to host
//serial_print("PID=IN:");
//serial_phex(stat);
//serial_print("\n");

// send remaining data, if any...
data = ep0_tx_ptr;
if (data) {
size = ep0_tx_len;
if (size > EP0_SIZE) size = EP0_SIZE;
endpoint0_transmit(data, size);
data += size;
ep0_tx_len -= size;
ep0_tx_ptr = (ep0_tx_len > 0 || size == EP0_SIZE) ? data : NULL;
}

if (setup.bRequest == 5 && setup.bmRequestType == 0) {
setup.bRequest = 0;
//serial_print("set address: ");
//serial_phex16(setup.wValue);
//serial_print("\n");
USB0_ADDR = setup.wValue;
}

break;
//default:
//serial_print("PID=unknown:");
//serial_phex(pid);
//serial_print("\n");
}
USB0_CTL = USB_CTL_USBENSOFEN; // clear TXSUSPENDTOKENBUSY bit
}



static usb_packet_t *rx_first[NUM_ENDPOINTS];
static usb_packet_t *rx_last[NUM_ENDPOINTS];
static usb_packet_t *tx_first[NUM_ENDPOINTS];
static usb_packet_t *tx_last[NUM_ENDPOINTS];

static uint8_t tx_state[NUM_ENDPOINTS];
#define TX_STATE_BOTH_FREE_EVEN_FIRST 0
#define TX_STATE_BOTH_FREE_ODD_FIRST 1
#define TX_STATE_EVEN_FREE 2
#define TX_STATE_ODD_FREE 3
#define TX_STATE_NONE_FREE 4



usb_packet_t *usb_rx(uint32_t endpoint)
{
usb_packet_t *ret;
endpoint--;
if (endpoint >= NUM_ENDPOINTS) return NULL;
__disable_irq();
ret = rx_first[endpoint];
if (ret) rx_first[endpoint] = ret->next;
__enable_irq();
//serial_print("rx, epidx=");
//serial_phex(endpoint);
//serial_print(", packet=");
//serial_phex32(ret);
//serial_print("\n");
return ret;
}

static uint32_t usb_queue_byte_count(const usb_packet_t *p)
{
uint32_t count=0;

__disable_irq();
for ( ; p; p = p->next) {
count += p->len;
}
__enable_irq();
return count;
}

uint32_t usb_rx_byte_count(uint32_t endpoint)
{
endpoint--;
if (endpoint >= NUM_ENDPOINTS) return 0;
return usb_queue_byte_count(rx_first[endpoint]);
}

uint32_t usb_tx_byte_count(uint32_t endpoint)
{
endpoint--;
if (endpoint >= NUM_ENDPOINTS) return 0;
return usb_queue_byte_count(tx_first[endpoint]);
}

uint32_t usb_tx_packet_count(uint32_t endpoint)
{
const usb_packet_t *p;
uint32_t count=0;

endpoint--;
if (endpoint >= NUM_ENDPOINTS) return 0;
p = tx_first[endpoint];
__disable_irq();
for ( ; p; p = p->next) count++;
__enable_irq();
return count;
}


// Called from usb_free, but only when usb_rx_memory_needed > 0, indicating
// receive endpoints are starving for memory. The intention is to give
// endpoints needing receive memory priority over the user's code, which is
// likely calling usb_malloc to obtain memory for transmitting. When the
// user is creating data very quickly, their consumption could starve reception
// without this prioritization. The packet buffer (input) is assigned to the
// first endpoint needing memory.
//
void usb_rx_memory(usb_packet_t *packet)
{
unsigned int i;
const uint8_t *cfg;

cfg = usb_endpoint_config_table;
//serial_print("rx_mem:");
__disable_irq();
for (i=1; i <= NUM_ENDPOINTS; i++) {
if (*cfg++ & USB_ENDPT_EPRXEN) {
if (table[index(i, RX, EVEN)].desc == 0) {
table[index(i, RX, EVEN)].addr = packet->buf;
table[index(i, RX, EVEN)].desc = BDT_DESC(64, 0);
usb_rx_memory_needed--;
__enable_irq();
//serial_phex(i);
//serial_print(",even\n");
return;
}
if (table[index(i, RX, ODD)].desc == 0) {
table[index(i, RX, ODD)].addr = packet->buf;
table[index(i, RX, ODD)].desc = BDT_DESC(64, 1);
usb_rx_memory_needed--;
__enable_irq();
//serial_phex(i);
//serial_print(",odd\n");
return;
}
}
}
__enable_irq();
// we should never reach this point. If we get here, it means
// usb_rx_memory_needed was set greater than zero, but no memory
// was actually needed.
usb_rx_memory_needed = 0;
usb_free(packet);
return;
}

//#define index(endpoint, tx, odd) (((endpoint) << 2) | ((tx) << 1) | (odd))
//#define stat2bufferdescriptor(stat) (table + ((stat) >> 2))

void usb_tx(uint32_t endpoint, usb_packet_t *packet)
{
bdt_t *b = &table[index(endpoint, TX, EVEN)];
uint8_t next;

endpoint--;
if (endpoint >= NUM_ENDPOINTS) return;
__disable_irq();
//serial_print("txstate=");
//serial_phex(tx_state[endpoint]);
//serial_print("\n");
switch (tx_state[endpoint]) {
case TX_STATE_BOTH_FREE_EVEN_FIRST:
next = TX_STATE_ODD_FREE;
break;
case TX_STATE_BOTH_FREE_ODD_FIRST:
b++;
next = TX_STATE_EVEN_FREE;
break;
case TX_STATE_EVEN_FREE:
next = TX_STATE_NONE_FREE;
break;
case TX_STATE_ODD_FREE:
b++;
next = TX_STATE_NONE_FREE;
break;
default:
if (tx_first[endpoint] == NULL) {
tx_first[endpoint] = packet;
} else {
tx_last[endpoint]->next = packet;
}
tx_last[endpoint] = packet;
__enable_irq();
return;
}
tx_state[endpoint] = next;
b->addr = packet->buf;
b->desc = BDT_DESC(packet->len, ((uint32_t)b & 8) ? DATA1 : DATA0);
__enable_irq();
}






void _reboot_Teensyduino_(void)
{
// TODO: initialize R0 with a code....
asm volatile("bkpt");
}



void usb_isr(void)
{
uint8_t status, stat, t;

//serial_print("isr");
//status = USB0_ISTAT;
//serial_phex(status);
//serial_print("\n");
restart:
status = USB0_ISTAT;

if ((status & USB_INTEN_SOFTOKEN /* 04 */ )) {
if (usb_configuration) {
t = usb_reboot_timer;
if (t) {
usb_reboot_timer = --t;
if (!t) _reboot_Teensyduino_();
}
#ifdef CDC_DATA_INTERFACE
t = usb_cdc_transmit_flush_timer;
if (t) {
usb_cdc_transmit_flush_timer = --t;
if (t == 0) usb_serial_flush_callback();
}
#endif
}
USB0_ISTAT = USB_INTEN_SOFTOKEN;
}

if ((status & USB_ISTAT_TOKDNE /* 08 */ )) {
uint8_t endpoint;
stat = USB0_STAT;
//serial_print("token: ep=");
//serial_phex(stat >> 4);
//serial_print(stat & 0x08 ? ",tx" : ",rx");
//serial_print(stat & 0x04 ? ",odd\n" : ",even\n");
endpoint = stat >> 4;
if (endpoint == 0) {
usb_control(stat);
} else {
bdt_t *b = stat2bufferdescriptor(stat);
usb_packet_t *packet = (usb_packet_t *)((uint8_t *)(b->addr) - 8);
#if 0
serial_print("ep:");
serial_phex(endpoint);
serial_print(", pid:");
serial_phex(BDT_PID(b->desc));
serial_print(((uint32_t)b & 8) ? ", odd" : ", even");
serial_print(", count:");
serial_phex(b->desc >> 16);
serial_print("\n");
#endif
endpoint--; // endpoint is index to zero-based arrays

if (stat & 0x08) { // transmit
usb_free(packet);
packet = tx_first[endpoint];
if (packet) {
//serial_print("tx packet\n");
tx_first[endpoint] = packet->next;
b->addr = packet->buf;
switch (tx_state[endpoint]) {
case TX_STATE_BOTH_FREE_EVEN_FIRST:
tx_state[endpoint] = TX_STATE_ODD_FREE;
break;
case TX_STATE_BOTH_FREE_ODD_FIRST:
tx_state[endpoint] = TX_STATE_EVEN_FREE;
break;
case TX_STATE_EVEN_FREE:
case TX_STATE_ODD_FREE:
default:
tx_state[endpoint] = TX_STATE_NONE_FREE;
break;
}
b->desc = BDT_DESC(packet->len, ((uint32_t)b & 8) ? DATA1 : DATA0);
} else {
//serial_print("tx no packet\n");
switch (tx_state[endpoint]) {
case TX_STATE_BOTH_FREE_EVEN_FIRST:
case TX_STATE_BOTH_FREE_ODD_FIRST:
break;
case TX_STATE_EVEN_FREE:
tx_state[endpoint] = TX_STATE_BOTH_FREE_EVEN_FIRST;
break;
case TX_STATE_ODD_FREE:
tx_state[endpoint] = TX_STATE_BOTH_FREE_ODD_FIRST;
break;
default:
tx_state[endpoint] = ((uint32_t)b & 8) ?
TX_STATE_ODD_FREE : TX_STATE_EVEN_FREE;
break;
}
}
} else { // receive
packet->len = b->desc >> 16;
packet->index = 0;
packet->next = NULL;
if (rx_first[endpoint] == NULL) {
//serial_print("rx 1st, epidx=");
//serial_phex(endpoint);
//serial_print(", packet=");
//serial_phex32((uint32_t)packet);
//serial_print("\n");
rx_first[endpoint] = packet;
} else {
//serial_print("rx Nth, epidx=");
//serial_phex(endpoint);
//serial_print(", packet=");
//serial_phex32((uint32_t)packet);
//serial_print("\n");
rx_last[endpoint]->next = packet;
}
rx_last[endpoint] = packet;
// TODO: implement a per-endpoint maximum # of allocated packets
// so a flood of incoming data on 1 endpoint doesn't starve
// the others if the user isn't reading it regularly
packet = usb_malloc();
if (packet) {
b->addr = packet->buf;
b->desc = BDT_DESC(64, ((uint32_t)b & 8) ? DATA1 : DATA0);
} else {
//serial_print("starving ");
//serial_phex(endpoint + 1);
//serial_print(((uint32_t)b & 8) ? ",odd\n" : ",even\n");
b->desc = 0;
usb_rx_memory_needed++;
}
}




}
USB0_ISTAT = USB_ISTAT_TOKDNE;
goto restart;
}



if (status & USB_ISTAT_USBRST /* 01 */ ) {
//serial_print("reset\n");

// initialize BDT toggle bits
USB0_CTL = USB_CTL_ODDRST;
ep0_tx_bdt_bank = 0;

// set up buffers to receive Setup and OUT packets
table[index(0, RX, EVEN)].desc = BDT_DESC(EP0_SIZE, 0);
table[index(0, RX, EVEN)].addr = ep0_rx0_buf;
table[index(0, RX, ODD)].desc = BDT_DESC(EP0_SIZE, 0);
table[index(0, RX, ODD)].addr = ep0_rx1_buf;
table[index(0, TX, EVEN)].desc = 0;
table[index(0, TX, ODD)].desc = 0;
// activate endpoint 0
USB0_ENDPT0 = USB_ENDPT_EPRXEN | USB_ENDPT_EPTXEN | USB_ENDPT_EPHSHK;

// clear all ending interrupts
USB0_ERRSTAT = 0xFF;
USB0_ISTAT = 0xFF;

// set the address to zero during enumeration
USB0_ADDR = 0;

// enable other interrupts
USB0_ERREN = 0xFF;
USB0_INTEN = USB_INTEN_TOKDNEEN |
USB_INTEN_SOFTOKEN |
USB_INTEN_STALLEN |
USB_INTEN_ERROREN |
USB_INTEN_USBRSTEN |
USB_INTEN_SLEEPEN;

// is this necessary?
USB0_CTL = USB_CTL_USBENSOFEN;
return;
}


if ((status & USB_ISTAT_STALL /* 80 */ )) {
//serial_print("stall:\n");
USB0_ENDPT0 = USB_ENDPT_EPRXEN | USB_ENDPT_EPTXEN | USB_ENDPT_EPHSHK;
USB0_ISTAT = USB_ISTAT_STALL;
}
if ((status & USB_ISTAT_ERROR /* 02 */ )) {
uint8_t err = USB0_ERRSTAT;
USB0_ERRSTAT = err;
//serial_print("err:");
//serial_phex(err);
//serial_print("\n");
USB0_ISTAT = USB_ISTAT_ERROR;
}

if ((status & USB_ISTAT_SLEEP /* 10 */ )) {
//serial_print("sleep\n");
USB0_ISTAT = USB_ISTAT_SLEEP;
}

}



void usb_init(void)
{
int i;

//serial_begin(BAUD2DIV(115200));
//serial_print("usb_init\n");

for (i=0; i <= NUM_ENDPOINTS*4; i++) {
table[i].desc = 0;
table[i].addr = 0;
}

// this basically follows the flowchart in the Kinetis
// Quick Reference User Guide, Rev. 1, 03/2012, page 141

// assume 48 MHz clock already running
// SIM - enable clock
SIM_SCGC4 |= SIM_SCGC4_USBOTG;

// reset USB module
USB0_USBTRC0 = USB_USBTRC_USBRESET;
while ((USB0_USBTRC0 & USB_USBTRC_USBRESET) != 0) ; // wait for reset to end

// set desc table base addr
USB0_BDTPAGE1 = ((uint32_t)table) >> 8;
USB0_BDTPAGE2 = ((uint32_t)table) >> 16;
USB0_BDTPAGE3 = ((uint32_t)table) >> 24;

// clear all ISR flags
USB0_ISTAT = 0xFF;
USB0_ERRSTAT = 0xFF;
USB0_OTGISTAT = 0xFF;

USB0_USBTRC0 |= 0x40; // undocumented bit

// enable USB
USB0_CTL = USB_CTL_USBENSOFEN;
USB0_USBCTRL = 0;

// enable reset interrupt
USB0_INTEN = USB_INTEN_USBRSTEN;

// enable interrupt in NVIC...
NVIC_ENABLE_IRQ(IRQ_USBOTG);

// enable d+ pullup
USB0_CONTROL = USB_CONTROL_DPPULLUPNONOTG;
}

// return 0 if the USB is not configured, or the configuration
// number selected by the HOST
uint8_t usb_configured(void)
{
return usb_configuration;
}



+ 38
- 0
USB/pjrc/arm/usb_dev.h View File

@@ -0,0 +1,38 @@
#ifndef _usb_dev_h_
#define _usb_dev_h_

// This header is NOT meant to be included when compiling
// user sketches in Arduino. The low-level functions
// provided by usb_dev.c are meant to be called only by
// code which provides higher-level interfaces to the user.

#include "usb_mem.h"
#include "usb_desc.h"

void usb_init(void);
uint8_t usb_configured(void); // is the USB port configured
void usb_isr(void);
usb_packet_t *usb_rx(uint32_t endpoint);
uint32_t usb_rx_byte_count(uint32_t endpoint);
uint32_t usb_tx_byte_count(uint32_t endpoint);
uint32_t usb_tx_packet_count(uint32_t endpoint);
void usb_tx(uint32_t endpoint, usb_packet_t *packet);
void usb_tx_isr(uint32_t endpoint, usb_packet_t *packet);

extern volatile uint8_t usb_configuration;

#ifdef CDC_DATA_INTERFACE
extern uint8_t usb_cdc_line_coding[7];
extern volatile uint8_t usb_cdc_line_rtsdtr;
extern volatile uint8_t usb_cdc_transmit_flush_timer;
extern void usb_serial_flush_callback(void);
#endif

#ifdef SEREMU_INTERFACE
extern volatile uint8_t usb_seremu_transmit_flush_timer;
extern void usb_seremu_flush_callback(void);
#endif


#endif


+ 52
- 0
USB/pjrc/arm/usb_keyboard.c View File

@@ -0,0 +1,52 @@
#include "usb_dev.h"
#include "usb_keyboard.h"
#include <Lib/USBLib.h>
#include <string.h> // for memcpy()


// Maximum number of transmit packets to queue so we don't starve other endpoints for memory
#define TX_PACKET_LIMIT 4

static uint8_t transmit_previous_timeout=0;

// When the PC isn't listening, how long do we wait before discarding data?
#define TX_TIMEOUT_MSEC 50

#if F_CPU == 96000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 596)
#elif F_CPU == 48000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 428)
#elif F_CPU == 24000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 262)
#endif


// send the contents of keyboard_keys and keyboard_modifier_keys
uint8_t usb_keyboard_send(void)
{
uint32_t wait_count=0;
usb_packet_t *tx_packet;

while (1) {
if (!usb_configuration) {
return -1;
}
if (usb_tx_packet_count(KEYBOARD_ENDPOINT) < TX_PACKET_LIMIT) {
tx_packet = usb_malloc();
if (tx_packet) break;
}
if (++wait_count > TX_TIMEOUT || transmit_previous_timeout) {
transmit_previous_timeout = 1;
return -1;
}
yield();
}
*(tx_packet->buf) = USBKeys_Modifiers;
*(tx_packet->buf + 1) = 0;
memcpy(tx_packet->buf + 2, USBKeys_Array, USB_MAX_KEY_SEND);
tx_packet->len = 8;
usb_tx(KEYBOARD_ENDPOINT, tx_packet);

return 0;
}


+ 10
- 0
USB/pjrc/arm/usb_keyboard.h View File

@@ -0,0 +1,10 @@
#ifndef USBkeyboard_h_
#define USBkeyboard_h_

#include <inttypes.h>
#include "usb_com.h"

uint8_t usb_keyboard_send(void);

#endif // USBkeyboard_h_


+ 78
- 0
USB/pjrc/arm/usb_mem.c View File

@@ -0,0 +1,78 @@
#include <Lib/USBLib.h>
#include "usb_dev.h"
#include "usb_mem.h"

#define NUM_BUF 30

__attribute__ ((section(".usbbuffers"), used))
//static unsigned char usb_buffer_memory[NUM_BUF * sizeof(usb_packet_t)];
unsigned char usb_buffer_memory[NUM_BUF * sizeof(usb_packet_t)];

static uint32_t usb_buffer_available = 0xFFFFFFFF;

// use bitmask and CLZ instruction to implement fast free list
// http://www.archivum.info/gnu.gcc.help/2006-08/00148/Re-GCC-Inline-Assembly.html
// http://gcc.gnu.org/ml/gcc/2012-06/msg00015.html
// __builtin_clz()

usb_packet_t * usb_malloc(void)
{
unsigned int n, avail;
uint8_t *p;

__disable_irq();
avail = usb_buffer_available;
n = __builtin_clz(avail); // clz = count leading zeros
if (n >= NUM_BUF) {
__enable_irq();
return NULL;
}
//serial_print("malloc:");
//serial_phex(n);
//serial_print("\n");

usb_buffer_available = avail & ~(0x80000000 >> n);
__enable_irq();
p = usb_buffer_memory + (n * sizeof(usb_packet_t));
//serial_print("malloc:");
//serial_phex32((int)p);
//serial_print("\n");
*(uint32_t *)p = 0;
*(uint32_t *)(p + 4) = 0;
return (usb_packet_t *)p;
}

// for the receive endpoints to request memory
extern uint8_t usb_rx_memory_needed;
extern void usb_rx_memory(usb_packet_t *packet);

void usb_free(usb_packet_t *p)
{
unsigned int n, mask;

//serial_print("free:");
n = ((uint8_t *)p - usb_buffer_memory) / sizeof(usb_packet_t);
if (n >= NUM_BUF) return;
//serial_phex(n);
//serial_print("\n");

// if any endpoints are starving for memory to receive
// packets, give this memory to them immediately!
if (usb_rx_memory_needed && usb_configuration) {
//serial_print("give to rx:");
//serial_phex32((int)p);
//serial_print("\n");
usb_rx_memory(p);
return;
}

mask = (0x80000000 >> n);
__disable_irq();
usb_buffer_available |= mask;
__enable_irq();

//serial_print("free:");
//serial_phex32((int)p);
//serial_print("\n");
}


+ 19
- 0
USB/pjrc/arm/usb_mem.h View File

@@ -0,0 +1,19 @@
#ifndef _usb_mem_h_
#define _usb_mem_h_

#include <stdint.h>

typedef struct usb_packet_struct {
uint16_t len;
uint16_t index;
struct usb_packet_struct *next;
uint8_t buf[64];
} usb_packet_t;

usb_packet_t * usb_malloc(void);
void usb_free(usb_packet_t *p);




#endif

+ 248
- 0
USB/pjrc/arm/usb_serial.c View File

@@ -0,0 +1,248 @@
#include "usb_dev.h"
#include "usb_serial.h"
#include <Lib/USBLib.h>

// defined by usb_dev.h -> usb_desc.h
#if defined(CDC_STATUS_INTERFACE) && defined(CDC_DATA_INTERFACE)

uint8_t usb_cdc_line_coding[7];
volatile uint8_t usb_cdc_line_rtsdtr=0;
volatile uint8_t usb_cdc_transmit_flush_timer=0;

static usb_packet_t *rx_packet=NULL;
static usb_packet_t *tx_packet=NULL;
static volatile uint8_t tx_noautoflush=0;

#define TRANSMIT_FLUSH_TIMEOUT 5 /* in milliseconds */

static void usb_serial_receive(void)
{
if (!usb_configuration) return;
if (rx_packet) return;
while (1) {
rx_packet = usb_rx(CDC_RX_ENDPOINT);
if (rx_packet == NULL) return;
if (rx_packet->len > 0) return;
usb_free(rx_packet);
rx_packet = NULL;
}
}

// get the next character, or -1 if nothing received
int usb_serial_getchar(void)
{
unsigned int i;
int c;

usb_serial_receive();
if (!rx_packet) return -1;
i = rx_packet->index;
c = rx_packet->buf[i++];
if (i >= rx_packet->len) {
usb_free(rx_packet);
rx_packet = NULL;
} else {
rx_packet->index = i;
}
return c;
}

// peek at the next character, or -1 if nothing received
int usb_serial_peekchar(void)
{
usb_serial_receive();
if (!rx_packet) return -1;
return rx_packet->buf[rx_packet->index];
}

// number of bytes available in the receive buffer
int usb_serial_available(void)
{
int count=0;

if (usb_configuration) {
count = usb_rx_byte_count(CDC_RX_ENDPOINT);
}
if (rx_packet) count += rx_packet->len - rx_packet->index;
return count;
}

// discard any buffered input
void usb_serial_flush_input(void)
{
usb_packet_t *rx;

if (!usb_configuration) return;
if (rx_packet) {
usb_free(rx_packet);
rx_packet = NULL;
}
while (1) {
rx = usb_rx(CDC_RX_ENDPOINT);
if (!rx) break;
usb_free(rx);
}
}

// Maximum number of transmit packets to queue so we don't starve other endpoints for memory
#define TX_PACKET_LIMIT 8

// When the PC isn't listening, how long do we wait before discarding data? If this is
// too short, we risk losing data during the stalls that are common with ordinary desktop
// software. If it's too long, we stall the user's program when no software is running.
#define TX_TIMEOUT_MSEC 70

#if F_CPU == 96000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 596)
#elif F_CPU == 48000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 428)
#elif F_CPU == 24000000
#define TX_TIMEOUT (TX_TIMEOUT_MSEC * 262)
#endif

// When we've suffered the transmit timeout, don't wait again until the computer
// begins accepting data. If no software is running to receive, we'll just discard
// data as rapidly as Serial.print() can generate it, until there's something to
// actually receive it.
static uint8_t transmit_previous_timeout=0;


// transmit a character. 0 returned on success, -1 on error
int usb_serial_putchar(uint8_t c)
{
#if 1
return usb_serial_write(&c, 1);
#endif
#if 0
uint32_t wait_count;

tx_noautoflush = 1;
if (!tx_packet) {
wait_count = 0;
while (1) {
if (!usb_configuration) {
tx_noautoflush = 0;
return -1;
}
if (usb_tx_packet_count(CDC_TX_ENDPOINT) < TX_PACKET_LIMIT) {
tx_noautoflush = 1;
tx_packet = usb_malloc();
if (tx_packet) break;
tx_noautoflush = 0;
}
if (++wait_count > TX_TIMEOUT || transmit_previous_timeout) {
transmit_previous_timeout = 1;
return -1;
}
}
}
transmit_previous_timeout = 0;
tx_packet->buf[tx_packet->index++] = c;
if (tx_packet->index < CDC_TX_SIZE) {
usb_cdc_transmit_flush_timer = TRANSMIT_FLUSH_TIMEOUT;
} else {
tx_packet->len = CDC_TX_SIZE;
usb_cdc_transmit_flush_timer = 0;
usb_tx(CDC_TX_ENDPOINT, tx_packet);
tx_packet = NULL;
}
tx_noautoflush = 0;
return 0;
#endif
}


int usb_serial_write(const void *buffer, uint32_t size)
{
#if 1
uint32_t len;
uint32_t wait_count;
const uint8_t *src = (const uint8_t *)buffer;
uint8_t *dest;

tx_noautoflush = 1;
while (size > 0) {
if (!tx_packet) {
wait_count = 0;
while (1) {
if (!usb_configuration) {
tx_noautoflush = 0;
return -1;
}
if (usb_tx_packet_count(CDC_TX_ENDPOINT) < TX_PACKET_LIMIT) {
tx_noautoflush = 1;
tx_packet = usb_malloc();
if (tx_packet) break;
tx_noautoflush = 0;
}
if (++wait_count > TX_TIMEOUT || transmit_previous_timeout) {
transmit_previous_timeout = 1;
return -1;
}
yield();
}
}
transmit_previous_timeout = 0;
len = CDC_TX_SIZE - tx_packet->index;
if (len > size) len = size;
dest = tx_packet->buf + tx_packet->index;
tx_packet->index += len;
size -= len;
while (len-- > 0) *dest++ = *src++;
if (tx_packet->index < CDC_TX_SIZE) {
usb_cdc_transmit_flush_timer = TRANSMIT_FLUSH_TIMEOUT;
} else {
tx_packet->len = CDC_TX_SIZE;
usb_cdc_transmit_flush_timer = 0;
usb_tx(CDC_TX_ENDPOINT, tx_packet);
tx_packet = NULL;
}
}
tx_noautoflush = 0;
return 0;
#endif
#if 0
const uint8_t *p = (const uint8_t *)buffer;
int r;

while (size) {
r = usb_serial_putchar(*p++);
if (r < 0) return -1;
size--;
}
return 0;
#endif
}

void usb_serial_flush_output(void)
{
if (!usb_configuration) return;
//serial_print("usb_serial_flush_output\n");
if (tx_packet && tx_packet->index > 0) {
usb_cdc_transmit_flush_timer = 0;
tx_packet->len = tx_packet->index;
usb_tx(CDC_TX_ENDPOINT, tx_packet);
tx_packet = NULL;
}
// while (usb_tx_byte_count(CDC_TX_ENDPOINT) > 0) ; // wait
}

void usb_serial_flush_callback(void)
{
if (tx_noautoflush) return;
//serial_print("usb_flush_callback \n");
tx_packet->len = tx_packet->index;
usb_tx(CDC_TX_ENDPOINT, tx_packet);
tx_packet = NULL;
//serial_print("usb_flush_callback end\n");
}









#endif // CDC_STATUS_INTERFACE && CDC_DATA_INTERFACE

+ 25
- 0
USB/pjrc/arm/usb_serial.h View File

@@ -0,0 +1,25 @@
#ifndef USBserial_h_
#define USBserial_h_

#include <inttypes.h>

// Compatibility defines from AVR
#define PROGMEM
#define PGM_P const char *
#define PSTR(str) (str)


int usb_serial_getchar(void);
int usb_serial_peekchar(void);
int usb_serial_available(void);
void usb_serial_flush_input(void);
int usb_serial_putchar(uint8_t c);
int usb_serial_write(const void *buffer, uint32_t size);
void usb_serial_flush_output(void);
extern uint8_t usb_cdc_line_coding[7];
extern volatile uint8_t usb_cdc_line_rtsdtr;
extern volatile uint8_t usb_cdc_transmit_flush_timer;
extern volatile uint8_t usb_configuration;

#endif // USBserial_h_


+ 10
- 22
USB/pjrc/avr/usb_keyboard_debug.c View File

@@ -274,18 +274,6 @@ static volatile uint8_t usb_configuration=0;
// packet, or send a zero length packet.
static volatile uint8_t debug_flush_timer=0;

// protocol setting from the host. We use exactly the same report
// either way, so this variable only stores the setting since we
// are required to be able to report which setting is in use.
static uint8_t keyboard_protocol=1;

// the idle configuration, how often we send the report to the
// host (ms * 4) even when it hasn't changed
static uint8_t keyboard_idle_config=125;

// count until idle timeout
static uint8_t keyboard_idle_count=0;


/**************************************************************************
*
@@ -344,7 +332,7 @@ int8_t usb_keyboard_send(void)
UEDATX = USBKeys_Array[i];
}
UEINTX = 0x3A;
keyboard_idle_count = 0;
USBKeys_Idle_Count = 0;
SREG = intr_state;
return 0;
}
@@ -461,12 +449,12 @@ ISR(USB_GEN_vect)
UEINTX = 0x3A;
}
}
if (keyboard_idle_config && (++div4 & 3) == 0) {
if (USBKeys_Idle_Config && (++div4 & 3) == 0) {
UENUM = KEYBOARD_ENDPOINT;
if (UEINTX & (1<<RWAL)) {
keyboard_idle_count++;
if (keyboard_idle_count == keyboard_idle_config) {
keyboard_idle_count = 0;
USBKeys_Idle_Count++;
if (USBKeys_Idle_Count == USBKeys_Idle_Config) {
USBKeys_Idle_Count = 0;
UEDATX = USBKeys_Modifiers;
UEDATX = 0;
for (i=0; i<6; i++) {
@@ -651,13 +639,13 @@ ISR(USB_COM_vect)
}
if (bRequest == HID_GET_IDLE) {
usb_wait_in_ready();
UEDATX = keyboard_idle_config;
UEDATX = USBKeys_Idle_Config;
usb_send_in();
return;
}
if (bRequest == HID_GET_PROTOCOL) {
usb_wait_in_ready();
UEDATX = keyboard_protocol;
UEDATX = USBKeys_Protocol;
usb_send_in();
return;
}
@@ -671,14 +659,14 @@ ISR(USB_COM_vect)
return;
}
if (bRequest == HID_SET_IDLE) {
keyboard_idle_config = (wValue >> 8);
keyboard_idle_count = 0;
USBKeys_Idle_Config = (wValue >> 8);
USBKeys_Idle_Count = 0;
//usb_wait_in_ready();
usb_send_in();
return;
}
if (bRequest == HID_SET_PROTOCOL) {
keyboard_protocol = wValue;
USBKeys_Protocol = wValue;
//usb_wait_in_ready();
usb_send_in();
return;

+ 12
- 0
USB/pjrc/usb_com.c View File

@@ -56,6 +56,18 @@
// 1=num lock, 2=caps lock, 4=scroll lock, 8=compose, 16=kana
volatile uint8_t USBKeys_LEDs = 0;

// protocol setting from the host. We use exactly the same report
// either way, so this variable only stores the setting since we
// are required to be able to report which setting is in use.
uint8_t USBKeys_Protocol = 1;

// the idle configuration, how often we send the report to the
// host (ms * 4) even when it hasn't changed
uint8_t USBKeys_Idle_Config = 125;

// count until idle timeout
uint8_t USBKeys_Idle_Count = 0;



// ----- Functions -----

+ 6
- 0
USB/pjrc/usb_com.h View File

@@ -60,8 +60,14 @@ extern uint8_t USBKeys_Modifiers;
extern uint8_t USBKeys_Array[USB_MAX_KEY_SEND];
extern uint8_t USBKeys_Sent;
extern volatile uint8_t USBKeys_LEDs;

static const uint8_t USBKeys_MaxSize = USB_MAX_KEY_SEND;

// Misc variables (XXX Some are only properly utilized using AVR)
extern uint8_t USBKeys_Protocol;
extern uint8_t USBKeys_Idle_Config;
extern uint8_t USBKeys_Idle_Count;



// ----- Functions -----

+ 3
- 0
arm.cmake View File

@@ -58,6 +58,9 @@ set( COMPILER_SRCS
Lib/delay.c
)

message( STATUS "Compiler Source Files:" )
message( "${COMPILER_SRCS}" )


#| Compiler flag to set the C Standard level.
#| c89 = "ANSI" C

+ 21
- 9
main.c View File

@@ -111,7 +111,17 @@ inline void usbTimerSetup(void)

// ARM
#elif defined(_mk20dx128_)
// TODO
// 48 MHz clock by default

// Enable Timers
/* TODO Fixme!!
PIT_MCR = 0x00;

// Setup ISR Timer for flagging a kepress send to USB
// 1 ms / (1 / 48 MHz) - 1 = 47999 cycles -> 0xBB7F
PIT_LDVAL0 = 0x0000BB7F;
PIT_TCTRL0 = 0x3; // Enable Timer 0 interrupts, and Enable Timer 0
*/
#endif
}

@@ -125,6 +135,7 @@ int main(void)
// Setup USB Module
usb_setup();

print("TEST");
// Setup ISR Timer for flagging a kepress send to USB
usbTimerSetup();

@@ -143,6 +154,10 @@ int main(void)
while ( scan_loop() );
sei();

// XXX DEBUG
dPrint("AAAAAAA\r\n");
print("AAAAAAB\r\n");

// Run Macros over Key Indices and convert to USB Keys
process_macros();

@@ -174,10 +189,12 @@ int main(void)

// ----- Interrupts -----

// AVR - USB Keyboard Data Send Counter Interrupt
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_)

// USB Keyboard Data Send Counter Interrupt
#if defined(_at90usb162_) || defined(_atmega32u4_) || defined(_at90usb646_) || defined(_at90usb1286_) // AVR
ISR( TIMER0_OVF_vect )
#elif defined(_mk20dx128_) // ARM
void pit0_isr(void)
#endif
{
sendKeypressCounter++;
if ( sendKeypressCounter > USB_TRANSFER_DIVIDER ) {
@@ -186,8 +203,3 @@ ISR( TIMER0_OVF_vect )
}
}

// ARM - USB Keyboard Data Send Counter Interrupt
#elif defined(_mk20dx128_)
// TODO
#endif


+ 1
- 1
setup.cmake View File

@@ -20,7 +20,7 @@
#| Please the {Scan,Macro,USB,Debug}/module.txt for information on the modules and how to create new ones

##| Deals with acquiring the keypress information and turning it into a key index
set( ScanModule "FACOM6684" )
set( ScanModule "MBC-55X" )

##| Uses the key index and potentially applies special conditions to it, mapping it to a usb key code
set( MacroModule "buffer" )