first commit

This commit is contained in:
Olaf Rempel 2008-02-03 21:41:39 +01:00
commit 1047706197
42 changed files with 6158 additions and 0 deletions

1
.gitignore vendored Normal file
View File

@ -0,0 +1 @@
build

75
Makefile Normal file
View File

@ -0,0 +1,75 @@
TOOLCHAIN = /opt/arm-toolchain
OPENOCD = /opt/arm-toolchain/openocd
AS = $(TOOLCHAIN)/bin/arm-elf-as
CC = $(TOOLCHAIN)/bin/arm-elf-gcc
LD = $(TOOLCHAIN)/bin/arm-elf-ld
NM = $(TOOLCHAIN)/bin/arm-elf-nm
SIZE = $(TOOLCHAIN)/bin/arm-elf-size
OBJCOPY = $(TOOLCHAIN)/bin/arm-elf-objcopy
OBJDUMP = $(TOOLCHAIN)/bin/arm-elf-objdump
INCDIRS = include $(TOOLCHAIN)/lib/gcc/arm-elf/4.1.1/include $(TOOLCHAIN)/arm-elf/include
LIBDIRS = $(TOOLCHAIN)/arm-elf/lib $(TOOLCHAIN)/lib/gcc/arm-elf/4.1.1
# ------
BUILD = build
TARGET = sam7fc
ASFLAGS = -mcpu=arm7tdmi -Wa,-adhlns=$(BUILD)/$(*D)/$(*F).lst,--gdwarf-2 -Iinclude
CFLAGS = -gdwarf-2 -mcpu=arm7tdmi -Os -std=gnu99
CFLAGS += -Wa,-adhlns=$(BUILD)/$(*D)/$(*F).lst
CFLAGS += -nostdinc $(patsubst %,-I%,$(INCDIRS))
CFLAGS += -MD -MP -MF $(BUILD)/.dep/$(*F).d
CFLAGS += -Wall
#CFLAGS += -Wextra
#CFLAGS += -Wcast-align -Wimplicit -Wunused
#CFLAGS += -Wpointer-arith -Wswitch
#CFLAGS += -Wredundant-decls -Wreturn-type -Wshadow
#CFLAGS += -Wbad-function-cast -Wsign-compare -Waggregate-return
#CFLAGS += -Wcast-qual -Wnested-externs
#CFLAGS += -Wmissing-prototypes
#CFLAGS += -Wstrict-prototypes -Wmissing-declarations
LDFLAGS = -nostartfiles -t ldscript.ld -Wl,-Map=$@.map,--cref
LDFLAGS += $(patsubst %,-L%,$(LIBDIRS))
LDFLAGS += -lc -lgcc
# ------
SRC := $(wildcard *.c) $(wildcard src/*.c) $(wildcard src/*/*.c)
AS_SRC := $(wildcard *.s) $(wildcard src/*.s)
all: $(BUILD)/$(TARGET).elf
@$(SIZE) -x $<
$(BUILD)/$(TARGET).elf: $(patsubst %,$(BUILD)/%,$(AS_SRC:.s=.o) $(SRC:.c=.o))
@echo " Linking file: $@"
@$(shell mkdir -p $(BUILD)/$(*D))
@$(CC) $(CFLAGS) $^ -o $@ $(LDFLAGS)
@$(OBJCOPY) -O binary $@ $@.bin
@$(OBJCOPY) -O ihex $@ $@.hex
@$(OBJDUMP) -h -S -C $@ > $@.lss
@$(NM) -n $@ > $@.sym
$(BUILD)/%.o: %.c
@echo " Building file: $<"
@$(shell mkdir -p $(BUILD)/$(*D))
@$(CC) -c $(CFLAGS) $< -o $@
$(BUILD)/%.o: %.s
@echo " Building file: $<"
@$(shell mkdir -p $(BUILD)/$(*D))
@$(CC) -c $(ASFLAGS) $< -o $@
clean:
rm -rf $(BUILD)
openocd:
$(shell $(OPENOCD) -f scripts/openocd.cfg)
-include $(shell mkdir -p $(BUILD)/.dep 2> /dev/null) $(wildcard $(BUILD)/.dep/*.d)

244
at91_init0.s Normal file
View File

@ -0,0 +1,244 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
.equ AIC_IVR, (256)
.equ AIC_FVR, (260)
.equ AIC_EOICR, (304)
.equ AT91C_BASE_AIC, (0xFFFFF000)
.equ IRQ_Stack_Size, (3 * 8 * 4)
.equ FIQ_Stack_Size, (3 * 8 * 4)
.equ ABT_Stack_Size, 192
.equ ARM_MODE_FIQ, 0x11
.equ ARM_MODE_IRQ, 0x12
.equ ARM_MODE_SVC, 0x13
.equ ARM_MODE_ABT, 0x17
.equ I_BIT, 0x80
.equ F_BIT, 0x40
.section .text
.global _start
.func _start
_start: ldr pc, [pc, #24] /* 0x00 Reset handler */
undefvec: ldr pc, [pc, #24] /* 0x04 Undefined Instruction */
swivec: ldr pc, [pc, #24] /* 0x08 Software Interrupt */
pabtvec: ldr pc, [pc, #24] /* 0x0C Prefetch Abort */
dabtvec: ldr pc, [pc, #24] /* 0x10 Data Abort */
rsvdvec: ldr pc, [pc, #24] /* 0x14 reserved */
irqvec: ldr pc, [pc, #24] /* 0x18 IRQ */
fiqvec: ldr pc, [pc, #24] /* 0x1c FIQ */
/* 0x80000000 will result in Prefetch Abort */
.word InitReset
.word 0x80000000
.word 0x80000000
.word ABT_Handler_Entry
.word ABT_Handler_Entry
.word 0x80000000
.word IRQ_Handler_Entry
.word FIQ_Handler_Entry
.endfunc
.global InitReset
.func InitReset
InitReset:
.extern at91_init1
/* Call Low level init function */
ldr sp,=__stack_top__
ldr r0,=at91_init1
mov lr, pc
bx r0
mov r0, sp
/* Setup FIQ Mode Stack */
msr CPSR_c, #ARM_MODE_FIQ | I_BIT | F_BIT
mov sp, r0
sub r0, r0, #FIQ_Stack_Size
/* store AIC Base in ARM_MODE_FIQ:r8 for faster access */
ldr r8, =AT91C_BASE_AIC
/* Setup IRQ Mode Stack */
msr CPSR_c, #ARM_MODE_IRQ | I_BIT | F_BIT
mov sp, r0
sub r0, r0, #IRQ_Stack_Size
/* Setup Abort Mode Stack */
msr CPSR_c, #ARM_MODE_ABT | I_BIT | F_BIT
mov sp, r0
sub r0, r0, #ABT_Stack_Size
/* Setup Supervisor Mode Stack (IRQ & NMI enabled) */
msr CPSR_c, #ARM_MODE_SVC
mov sp, r0
/* Relocate .data section */
ldr r1, =__text_end__
ldr r2, =__data_start__
ldr r3, =__data_end__
LoopRel: cmp r2, r3
ldrlo r0, [r1], #4
strlo r0, [r2], #4
blo LoopRel
/* Clear .bss section */
mov r0, #0
ldr r1, =__bss_start__
ldr r2, =__bss_end__
LoopZI: cmp r1, r2
strlo r0, [r1], #4
BLO LoopZI
/* Start main() */
ldr lr,=exit
ldr r0,=main
bx r0
.endfunc
.global exit
.func exit
/* exit dummy for newlib */
exit: b .
.endfunc
.global ABT_Handler_Entry
.func ABT_Handler_Entry
ABT_Handler_Entry:
/* disable interrupts (F_BIT not set on entry) */
msr CPSR_c, #ARM_MODE_ABT | I_BIT | F_BIT
/* store all registers */
stmfd sp!, { r0-r12 }
/* saved cpsr (from aborted mode) */
mrs r0, SPSR
/* address of abort (pc) */
mov r3, lr
/* enter previous mode and get lr(r14), sp(r13) */
/* TODO: interrupts might be enabled? */
/* TODO: thumb mode enabled? */
msr CPSR_c, r0
mov r1, sp
mov r2, lr
/* return to abort mode */
msr CPSR_c, #ARM_MODE_ABT | I_BIT | F_BIT
/* store remaining registers (r1-r3 == r13-r15) */
stmfd sp!, { r1-r3 }
mov r1, sp
/* execute C Handler (cpsr, registers) */
ldr r5,=at91_abt_handler
mov lr, pc
bx r5
b .
.endfunc
.global FIQ_Handler_Entry
.func FIQ_Handler_Entry
FIQ_Handler_Entry:
/* Save r0 to ARM_MODE_FIQ:r9 */
mov r9,r0
/* get FIQ Vector from AIC and thus clear FIQ */
ldr r0 , [r8, #AIC_FVR]
/* Switch to ARM_MODE_SVC and save registers there */
msr CPSR_c,#ARM_MODE_SVC | I_BIT | F_BIT
stmfd sp!, { r1-r3, r12, lr}
/* execute FIQ in SVC_MODE */
mov r14, pc
bx r0
/* restore registers and switch back to ARM_MODE_FIQ */
ldmia sp!, { r1-r3, r12, lr}
msr CPSR_c, #ARM_MODE_FIQ | I_BIT | F_BIT
/* restore the ARM_MODE_SVC:r0 */
mov r0,r9
/* restore PC using the LR_fiq directly */
subs pc,lr,#4
.endfunc
.global IRQ_Handler_Entry
.func IRQ_Handler_Entry
IRQ_Handler_Entry:
/*- Manage Exception Entry */
/*- Adjust and save LR_irq in IRQ stack */
sub lr, lr, #4
stmfd sp!, {lr}
/*- Save SPSR need to be saved for nested interrupt */
mrs r14, SPSR
stmfd sp!, {r14}
/*- Save and r0 in IRQ stack */
stmfd sp!, {r0}
/*- Write in the IVR to support Protect Mode */
/*- No effect in Normal Mode */
/*- De-assert the NIRQ and clear the source in Protect Mode */
ldr r14, =AT91C_BASE_AIC
ldr r0 , [r14, #AIC_IVR]
str r14, [r14, #AIC_IVR]
/*- Enable Interrupt and Switch in Supervisor Mode */
msr CPSR_c, #ARM_MODE_SVC
/*- Save scratch/used registers and LR in User Stack */
stmfd sp!, { r1-r3, r12, r14}
/*- Branch to the routine pointed by the AIC_IVR */
mov r14, pc
bx r0
/*- Restore scratch/used registers and LR from User Stack*/
ldmia sp!, { r1-r3, r12, r14}
/*- Disable Interrupt and switch back in IRQ mode */
msr CPSR_c, #ARM_MODE_IRQ | I_BIT
/*- Mark the End of Interrupt on the AIC */
ldr r14, =AT91C_BASE_AIC
str r14, [r14, #AIC_EOICR]
/*- Restore SPSR_irq and r0 from IRQ stack */
ldmia sp!, {r0}
/*- Restore SPSR_irq and r0 from IRQ stack */
ldmia sp!, {r14}
msr SPSR_cxsf, r14
/*- Restore adjusted LR_irq from IRQ stack directly in the PC */
ldmia sp!, {pc}^
.endfunc
.end

81
at91_init1.c Normal file
View File

@ -0,0 +1,81 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include "AT91SAM7S256.h"
static void empty_isr(void) {}
/*
* Init critical onchip hardware:
* - disable Watchdog
* - enable Oscillator and PLL, switch to 48MHz MCK
* - set empty Interrupt Handlers
*/
void at91_init1(void)
{
/* disable watchdog */
*AT91C_WDTC_WDMR = AT91C_WDTC_WDDIS;
/* enable user reset */
*AT91C_RSTC_RMR = (AT91C_RSTC_KEY & 0xA5 << 24) | AT91C_RSTC_URSTEN;
/* Set Flash Waitstates */
*AT91C_MC_FMR = AT91C_MC_FWS_1FWS;
/*
* Enable main oscillator (MAINCK)
* startup time: 8*6/32768 -> 1.46ms
*/
AT91S_PMC *pmc = AT91C_BASE_PMC;
pmc->PMC_MOR = (AT91C_CKGR_OSCOUNT & (6<<8)) |
AT91C_CKGR_MOSCEN;
while (!(pmc->PMC_SR & AT91C_PMC_MOSCS));
/*
* PLLCK = 18.432MHz / 24 * 125 = 96MHz -> div:24, mul:124
* startup time: 32/32768 -> 976us
*/
pmc->PMC_PLLR = (AT91C_CKGR_DIV & 24) |
(AT91C_CKGR_MUL & (124<<16)) |
(AT91C_CKGR_PLLCOUNT & (32<<8)) ;
while (!(pmc->PMC_SR & AT91C_PMC_LOCK));
/* MCK = PLLCK / 2 = 48MHz */
pmc->PMC_MCKR = AT91C_PMC_CSS_PLL_CLK |
AT91C_PMC_PRES_CLK_2;
while (!(pmc->PMC_SR & AT91C_PMC_MCKRDY));
/* enable protected mode (let AIC work with debugger) */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_DCR = AT91C_AIC_DCR_PROT;
/* Disable & clear all Interrupts */
aic->AIC_IDCR = ~0;
aic->AIC_ICCR = ~0;
/* default Interrupt Handlers just return */
aic->AIC_FVR = (uint32_t)empty_isr;
aic->AIC_IVR = (uint32_t)empty_isr;
uint32_t i;
for (i = 0; i < 32; i++) {
aic->AIC_SMR[i] = 0;
aic->AIC_SVR[i] = (uint32_t)empty_isr;
}
aic->AIC_SPU = (uint32_t)empty_isr;
}

1918
include/AT91SAM7S256.h Normal file

File diff suppressed because it is too large Load Diff

12
include/at91_dbgu.h Normal file
View File

@ -0,0 +1,12 @@
#ifndef AT91_DBGU_H_
#define AT91_DBGU_H_
#include <stddef.h>
void at91_dbgu_init(void);
void at91_dbgu_putc(char c);
void at91_dbgu_puts(const char *p);
int at91_dbgu_write(void *base, const char *buf, size_t len);
#endif /*AT91_DBGU_H_*/

20
include/at91_pio.h Normal file
View File

@ -0,0 +1,20 @@
#ifndef AT91_PIO_H_
#define AT91_PIO_H_
#include <stdint.h>
struct pio_pinchange_isr {
uint32_t mask;
void (*func)(uint32_t status, uint32_t input);
};
#define PIO_PINCHANGE_ISR(mask, func) \
static struct pio_pinchange_isr \
__attribute__((used, section(".pio_isr"))) \
pio_isr_##func = { mask, &func };
void pio_trigger_isr(uint32_t mask);
void at91_pio_init(void);
#endif /*AT91_PIO_H_*/

25
include/at91_pitc.h Normal file
View File

@ -0,0 +1,25 @@
#ifndef AT91_PITC_H_
#define AT91_PITC_H_
#include <stdint.h>
#include <stddef.h>
#include "list.h"
#define PITC_RESTART_TIMER 0
#define PITC_REMOVE_TIMER 1
struct pitc_timer {
struct list_head list;
uint32_t interval;
uint32_t nextrun;
uint32_t (*func)(struct pitc_timer *);
void *privdata;
};
void pitc_schedule_timer(struct pitc_timer *timer);
struct pitc_timer * alloc_pitc_timer(uint32_t interval, uint32_t (*func)(struct pitc_timer *), void *privdata);
uint32_t pitc_get_ticks(void);
void at91_pitc_init(void);
#endif /*AT91_PITC_H_*/

22
include/at91_sysc.h Normal file
View File

@ -0,0 +1,22 @@
#ifndef AT91_SYSC_H_
#define AT91_SYSC_H_
#include <stdint.h>
enum syscirqs {
AT91_SYSIRQ_PIT = 0,
AT91_SYSIRQ_DBGU = 1,
AT91_SYSIRQ_EFC = 2,
AT91_SYSIRQ_WDT = 3,
AT91_SYSIRQ_RTT = 4,
AT91_SYSIRQ_RSTC = 5,
AT91_SYSIRQ_PMC = 6,
AT91_SYSIRQ_COUNT
};
typedef void SYSCISR(uint32_t status);
void at91_sysc_init(void);
void sysc_register_isr(enum syscirqs irq, SYSCISR *isr);
#endif /*AT91_SYSC_H_*/

14
include/at91_tc1.h Normal file
View File

@ -0,0 +1,14 @@
#ifndef RC_PPM_H_
#define RC_PPM_H_
#define MAX_CHANNELS 8
struct rc_values {
int16_t ch[MAX_CHANNELS];
uint32_t count;
};
void at91_tc1_init(void);
uint32_t rc_ppm_getvalues(struct rc_values *rc);
#endif /*RC_PPM_H_*/

9
include/at91_tests.h Normal file
View File

@ -0,0 +1,9 @@
#ifndef AT91_TESTS_H_
#define AT91_TESTS_H_
void at91_rttc_test_init(void);
void at91_adc_test_init(void);
void at91_adc_printresults(void);
#endif /*AT91_TESTS_H_*/

57
include/at91_twi.h Normal file
View File

@ -0,0 +1,57 @@
#ifndef AT91TWI_H_
#define AT91TWI_H_
#include <list.h>
/* TWI slave addresses */
#define TWI_ADDR_BL1 0x21
#define TWI_ADDR_BL2 0x22
#define TWI_ADDR_BL3 0x23
#define TWI_ADDR_BL4 0x24
#define TWI_ADDR_EEPROM 0x40
/* TWIBOOT commands */
#define CMD_WAIT 0x00
#define CMD_GET_INFO 0x10
#define CMD_GET_SIGNATURE 0x11
#define CMD_WRITE_FLASH 0x12
#define CMD_READ_FLASH 0x13
#define CMD_WRITE_EEPROM 0x14
#define CMD_READ_EEPROM 0x15
#define CMD_BOOT_APPLICATION 0x1F
/* blctrl commands */
//#define CMD_WAIT 0x00
//#define CMD_GET_INFO 0x10
#define CMD_SET_PWM 0x21
#define CMD_GET_STATUS 0x22
//#define CMD_SET_PARAM 0x23
//#define CMD_GET_PARAM 0x24
#define CMD_BOOT_LOADER 0x2F
struct blmc_cmd {
uint32_t cmd; /* cmd byte(s) */
uint8_t mode; /* read/write, cmdlen (1-3 bytes) */
uint8_t size; /* data size */
uint8_t *data; /* read/write data */
};
/* same bits as TWI_MMR[8..15] */
#define BLMC_CMD_READ 0x10
#define BLMC_CMD_WRITE 0x00
#define BLMC_CMD_0_ARG 0x01
#define BLMC_CMD_1_ARG 0x02
#define BLMC_CMD_2_ARG 0x03
uint32_t twi_read_eeprom(uint32_t addr, uint8_t *buf, uint32_t size);
uint32_t twi_write_eeprom(uint32_t addr, uint8_t *buf, uint32_t size);
uint32_t twi_setpwm(uint8_t *values);
uint32_t twi_cmd(uint8_t addr, struct blmc_cmd *cmd);
void at91_twi_init(void);
void at91_twi_test(void);
#endif /*AT91TWI_H_*/

6
include/at91_udp.h Normal file
View File

@ -0,0 +1,6 @@
#ifndef AT91_UDP_H_
#define AT91_UDP_H_
void at91_udp_init(void);
#endif /*AT91_UDP_H_*/

26
include/atomic.h Normal file
View File

@ -0,0 +1,26 @@
#ifndef ATOMIC_H_
#define ATOMIC_H_
//TODO: not for thumbcode?!
#define disable_irqs() \
{ \
int temp_; \
asm volatile ( \
"mrs %0, cpsr" "\n\t" \
"stmfd sp!, {%0}" "\n\t" \
"orr %0, %0, #0xC0" "\n\t" \
"msr cpsr, %0" "\n\t" \
: "=r" (temp_) : ); \
}
#define restore_irqs() \
{ \
int temp_; \
asm volatile ( \
"ldmfd sp!, {%0}" "\n\t" \
"msr cpsr, %0" "\n\t" \
: "=r" (temp_) : ); \
}
#endif /*ATOMIC_H_*/

43
include/board.h Normal file
View File

@ -0,0 +1,43 @@
#ifndef BOARD_H_
#define BOARD_H_
#include "AT91SAM7S256.h"
/* keep in sync with at91_init1.c */
#define MAINCK 18432000
#define PLLCK (MAINCK / 24 * 125) /* 96MHz */
#define MCK (PLLCK / 2) /* 48MHz */
/* DBGU UART Baudrate calculation */
#define BAUD_TO_DIV(BAUD) (MCK / (16 * BAUD))
/* LED PIOs */
#define LED_ORANGE AT91C_PIO_PA17
#define LED_GREEN AT91C_PIO_PA18
/* Taster PIOs */
#define TAST1 AT91C_PIO_PA19
#define TAST2 AT91C_PIO_PA20
/* USB PIOs */
#define UDP_VBUS_MON AT91C_PIO_PA24
#define UDP_PULLUP AT91C_PIO_PA25
/* ATMEL IDs */
#define USB_VENDOR_ID 0x03EB
#define USB_PRODUCT_ID 0x6124
/* Interrupt Priorities (7 = highest) */
#define IRQPRIO_SYSC 6 /* pitc */
#define IRQPRIO_PIOA 1 /* pinchange interrupts */
#define IRQPRIO_ADC 2
#define IRQPRIO_TWI 7 /* twi must be fast! */
#define IRQPRIO_UDP 4 /* usb */
#define IRQPRIO_TC1 5 /* ppm capturing */
/* TODO: find better place */
#define ARRAY_SIZE(x) (sizeof(x) / sizeof(*x))
#define MIN(a,b) ((a) < (b) ? (a) : (b))
#define MAX(a,b) ((a) > (b) ? (a) : (b))
#endif /*BOARD_H_*/

28
include/fifo.h Normal file
View File

@ -0,0 +1,28 @@
#ifndef FIFO_H_
#define FIFO_H_
#include <stdint.h>
struct fifo {
uint32_t in;
uint32_t out;
uint16_t pdc_tx;
uint16_t pdc_rx;
uint32_t size;
char buf[0];
};
uint32_t fifo_put(struct fifo *fifo, const char *buf, uint32_t len);
uint32_t fifo_get(struct fifo *fifo, char *buf, uint32_t len);
uint32_t fifo_rxpdc(struct fifo *fifo, AT91S_PDC *pdc, uint16_t maxsize);
uint32_t fifo_txpdc(struct fifo *fifo, AT91S_PDC *pdc, uint16_t maxsize);
uint32_t fifo_putbyte(struct fifo *fifo, char c);
uint32_t fifo_getbyte(struct fifo *fifo, char *p);
struct fifo * fifo_alloc(uint32_t size);
#endif /*FIFO_H_*/

268
include/list.h Normal file
View File

@ -0,0 +1,268 @@
#ifndef _LIST_H_
#define _LIST_H_
/*
* stolen from linux kernel 2.6.11 (http://kernel.org/)
* linux/include/linux/stddef.h (offsetoff)
* linux/include/linux/kernel.h (container_of)
* linux/include/linux/list.h (*list*)
* linux/include/linux/netfilter_ipv4/listhelp.h (LIST_FIND)
*
* modified by Olaf Rempel <razzor@kopf-tisch.de>
*/
//#define offsetof(TYPE, MEMBER) ((size_t) &((TYPE *)0)->MEMBER)
#define container_of(ptr, type, member) ({ \
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
(type *)( (char *)__mptr - offsetof(type,member) );})
struct list_head {
struct list_head *next, *prev;
};
#define LIST_HEAD_INIT(name) { &(name), &(name) }
#define LIST_HEAD(name) \
struct list_head name = LIST_HEAD_INIT(name)
#define INIT_LIST_HEAD(ptr) do { \
(ptr)->next = (ptr); (ptr)->prev = (ptr); \
} while (0)
/*
* Insert a new entry between two known consecutive entries.
*
* This is only for internal list manipulation where we know
* the prev/next entries already!
*/
static inline void __list_add(struct list_head *new,
struct list_head *prev,
struct list_head *next)
{
next->prev = new;
new->next = next;
new->prev = prev;
prev->next = new;
}
/*
* list_add - add a new entry
* @new: new entry to be added
* @head: list head to add it after
*
* Insert a new entry after the specified head.
* This is good for implementing stacks.
*/
static inline void list_add(struct list_head *new, struct list_head *head)
{
__list_add(new, head, head->next);
}
/*
* list_add_tail - add a new entry
* @new: new entry to be added
* @head: list head to add it before
*
* Insert a new entry before the specified head.
* This is useful for implementing queues.
*/
static inline void list_add_tail(struct list_head *new, struct list_head *head)
{
__list_add(new, head->prev, head);
}
/*
* Delete a list entry by making the prev/next entries
* point to each other.
*
* This is only for internal list manipulation where we know
* the prev/next entries already!
*/
static inline void __list_del(struct list_head * prev, struct list_head * next)
{
next->prev = prev;
prev->next = next;
}
/*
* list_del - deletes entry from list.
* @entry: the element to delete from the list.
* Note: list_empty on entry does not return true after this, the entry is
* in an undefined state.
*/
static inline void list_del(struct list_head *entry)
{
__list_del(entry->prev, entry->next);
entry->next = NULL;
entry->prev = NULL;
}
/*
* list_del_init - deletes entry from list and reinitialize it.
* entry: the element to delete from the list.
*/
static inline void list_del_init(struct list_head *entry)
{
__list_del(entry->prev, entry->next);
INIT_LIST_HEAD(entry);
}
/*
* list_move - delete from one list and add as another's head
* @list: the entry to move
* @head: the head that will precede our entry
*/
static inline void list_move(struct list_head *list, struct list_head *head)
{
__list_del(list->prev, list->next);
list_add(list, head);
}
/*
* list_move_tail - delete from one list and add as another's tail
* @list: the entry to move
* @head: the head that will follow our entry
*/
static inline void list_move_tail(struct list_head *list,
struct list_head *head)
{
__list_del(list->prev, list->next);
list_add_tail(list, head);
}
/*
* list_empty - tests whether a list is empty
* @head: the list to test.
*/
static inline int list_empty(const struct list_head *head)
{
return head->next == head;
}
static inline void __list_splice(struct list_head *list,
struct list_head *head)
{
struct list_head *first = list->next;
struct list_head *last = list->prev;
struct list_head *at = head->next;
first->prev = head;
head->next = first;
last->next = at;
at->prev = last;
}
/*
* list_splice - join two lists
* @list: the new list to add.
* @head: the place to add it in the first list.
*/
static inline void list_splice(struct list_head *list, struct list_head *head)
{
if (!list_empty(list))
__list_splice(list, head);
}
/*
* list_splice_init - join two lists and reinitialise the emptied list.
* @list: the new list to add.
* @head: the place to add it in the first list.
*
* The list at @list is reinitialised
*/
static inline void list_splice_init(struct list_head *list,
struct list_head *head)
{
if (!list_empty(list)) {
__list_splice(list, head);
INIT_LIST_HEAD(list);
}
}
/*
* list_entry - get the struct for this entry
* @ptr: the &struct list_head pointer.
* @type: the type of the struct this is embedded in.
* @member: the name of the list_struct within the struct.
*/
#define list_entry(ptr, type, member) \
container_of(ptr, type, member)
/*
* list_for_each - iterate over a list
* @pos: the &struct list_head to use as a loop counter.
* @head: the head for your list.
*/
#define list_for_each(pos, head) \
for (pos = (head)->next; pos != (head); pos = pos->next)
/*
* list_for_each_prev - iterate over a list backwards
* @pos: the &struct list_head to use as a loop counter.
* @head: the head for your list.
*/
#define list_for_each_prev(pos, head) \
for (pos = (head)->prev; pos != (head); pos = pos->prev)
/*
* list_for_each_safe - iterate over a list safe against removal of list entry
* @pos: the &struct list_head to use as a loop counter.
* @n: another &struct list_head to use as temporary storage
* @head: the head for your list.
*/
#define list_for_each_safe(pos, n, head) \
for (pos = (head)->next, n = pos->next; pos != (head); \
pos = n, n = pos->next)
/*
* list_for_each_entry - iterate over list of given type
* @pos: the type * to use as a loop counter.
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define list_for_each_entry(pos, head, member) \
for (pos = list_entry((head)->next, typeof(*pos), member); \
&pos->member != (head); \
pos = list_entry(pos->member.next, typeof(*pos), member))
/*
* list_for_each_entry_reverse - iterate backwards over list of given type.
* @pos: the type * to use as a loop counter.
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define list_for_each_entry_reverse(pos, head, member) \
for (pos = list_entry((head)->prev, typeof(*pos), member); \
&pos->member != (head); \
pos = list_entry(pos->member.prev, typeof(*pos), member))
/*
* list_for_each_entry_safe - iterate over list of given type safe against removal of list entry
* @pos: the type * to use as a loop counter.
* @n: another type * to use as temporary storage
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define list_for_each_entry_safe(pos, n, head, member) \
for (pos = list_entry((head)->next, typeof(*pos), member), \
n = list_entry(pos->member.next, typeof(*pos), member); \
&pos->member != (head); \
pos = n, n = list_entry(n->member.next, typeof(*n), member))
/* Return pointer to first true entry, if any, or NULL. A macro
required to allow inlining of cmpfn. */
#define LIST_FIND(head, cmpfn, type, args...) \
({ \
const struct list_head *__i, *__j = NULL; \
\
list_for_each(__i, (head)) \
if (cmpfn((const type)__i , ## args)) { \
__j = __i; \
break; \
} \
(type)__j; \
})
#endif /* _LIST_H_ */

9
include/static_alloc.h Normal file
View File

@ -0,0 +1,9 @@
#ifndef STATIC_ALLOC_H_
#define STATIC_ALLOC_H_
void * static_alloc(uint32_t size);
uint32_t static_alloc_used(void);
uint32_t next_powerof2(uint32_t value);
#endif /*STATIC_ALLOC_H_*/

240
include/usb_cdc.h Normal file
View File

@ -0,0 +1,240 @@
#ifndef USB_CDC_H_
#define USB_CDC_H_
#include <stdint.h>
/*
* the content of this file comes from
* - linux/include/linux/usb/cdc.h
* with minor modifications:
* - type conversion (e.g. __u8 -> uint8_t)
*/
/*-------------------------------------------------------------------------*/
/*
* USB Communications Device Class (CDC) definitions
*
* CDC says how to talk to lots of different types of network adapters,
* notably ethernet adapters and various modems. It's used mostly with
* firmware based USB peripherals.
*/
#define USB_CDC_SUBCLASS_ACM 0x02
#define USB_CDC_SUBCLASS_ETHERNET 0x06
#define USB_CDC_SUBCLASS_WHCM 0x08
#define USB_CDC_SUBCLASS_DMM 0x09
#define USB_CDC_SUBCLASS_MDLM 0x0a
#define USB_CDC_SUBCLASS_OBEX 0x0b
#define USB_CDC_PROTO_NONE 0
#define USB_CDC_ACM_PROTO_AT_V25TER 1
#define USB_CDC_ACM_PROTO_AT_PCCA101 2
#define USB_CDC_ACM_PROTO_AT_PCCA101_WAKE 3
#define USB_CDC_ACM_PROTO_AT_GSM 4
#define USB_CDC_ACM_PROTO_AT_3G 5
#define USB_CDC_ACM_PROTO_AT_CDMA 6
#define USB_CDC_ACM_PROTO_VENDOR 0xff
/*-------------------------------------------------------------------------*/
/*
* Class-Specific descriptors ... there are a couple dozen of them
*/
#define USB_CDC_HEADER_TYPE 0x00 /* header_desc */
#define USB_CDC_CALL_MANAGEMENT_TYPE 0x01 /* call_mgmt_descriptor */
#define USB_CDC_ACM_TYPE 0x02 /* acm_descriptor */
#define USB_CDC_UNION_TYPE 0x06 /* union_desc */
#define USB_CDC_COUNTRY_TYPE 0x07
#define USB_CDC_NETWORK_TERMINAL_TYPE 0x0a /* network_terminal_desc */
#define USB_CDC_ETHERNET_TYPE 0x0f /* ether_desc */
#define USB_CDC_WHCM_TYPE 0x11
#define USB_CDC_MDLM_TYPE 0x12 /* mdlm_desc */
#define USB_CDC_MDLM_DETAIL_TYPE 0x13 /* mdlm_detail_desc */
#define USB_CDC_DMM_TYPE 0x14
#define USB_CDC_OBEX_TYPE 0x15
/* "Header Functional Descriptor" from CDC spec 5.2.3.1 */
struct usb_cdc_header_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint16_t bcdCDC;
} __attribute__ ((packed));
/* "Call Management Descriptor" from CDC spec 5.2.3.2 */
struct usb_cdc_call_mgmt_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t bmCapabilities;
#define USB_CDC_CALL_MGMT_CAP_CALL_MGMT 0x01
#define USB_CDC_CALL_MGMT_CAP_DATA_INTF 0x02
uint8_t bDataInterface;
} __attribute__ ((packed));
/* "Abstract Control Management Descriptor" from CDC spec 5.2.3.3 */
struct usb_cdc_acm_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t bmCapabilities;
} __attribute__ ((packed));
/* capabilities from 5.2.3.3 */
#define USB_CDC_COMM_FEATURE 0x01
#define USB_CDC_CAP_LINE 0x02
#define USB_CDC_CAP_BRK 0x04
#define USB_CDC_CAP_NOTIFY 0x08
/* "Union Functional Descriptor" from CDC spec 5.2.3.8 */
struct usb_cdc_union_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t bMasterInterface0;
uint8_t bSlaveInterface0;
/* ... and there could be other slave interfaces */
} __attribute__ ((packed));
/* "Country Selection Functional Descriptor" from CDC spec 5.2.3.9 */
struct usb_cdc_country_functional_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t iCountryCodeRelDate;
uint16_t wCountyCode0;
/* ... and there can be a lot of country codes */
} __attribute__ ((packed));
/* "Network Channel Terminal Functional Descriptor" from CDC spec 5.2.3.11 */
struct usb_cdc_network_terminal_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t bEntityId;
uint8_t iName;
uint8_t bChannelIndex;
uint8_t bPhysicalInterface;
} __attribute__ ((packed));
/* "Ethernet Networking Functional Descriptor" from CDC spec 5.2.3.16 */
struct usb_cdc_ether_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint8_t iMACAddress;
uint32_t bmEthernetStatistics;
uint16_t wMaxSegmentSize;
uint16_t wNumberMCFilters;
uint8_t bNumberPowerFilters;
} __attribute__ ((packed));
/* "MDLM Functional Descriptor" from CDC WMC spec 6.7.2.3 */
struct usb_cdc_mdlm_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
uint16_t bcdVersion;
uint8_t bGUID[16];
} __attribute__ ((packed));
/* "MDLM Detail Functional Descriptor" from CDC WMC spec 6.7.2.4 */
struct usb_cdc_mdlm_detail_desc {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubType;
/* type is associated with mdlm_desc.bGUID */
uint8_t bGuidDescriptorType;
uint8_t bDetailData[0];
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
/*
* Class-Specific Control Requests (6.2)
*
* section 3.6.2.1 table 4 has the ACM profile, for modems.
* section 3.8.2 table 10 has the ethernet profile.
*
* Microsoft's RNDIS stack for Ethernet is a vendor-specific CDC ACM variant,
* heavily dependent on the encapsulated (proprietary) command mechanism.
*/
#define USB_CDC_SEND_ENCAPSULATED_COMMAND 0x00
#define USB_CDC_GET_ENCAPSULATED_RESPONSE 0x01
#define USB_CDC_REQ_SET_LINE_CODING 0x20
#define USB_CDC_REQ_GET_LINE_CODING 0x21
#define USB_CDC_REQ_SET_CONTROL_LINE_STATE 0x22
#define USB_CDC_REQ_SEND_BREAK 0x23
#define USB_CDC_SET_ETHERNET_MULTICAST_FILTERS 0x40
#define USB_CDC_SET_ETHERNET_PM_PATTERN_FILTER 0x41
#define USB_CDC_GET_ETHERNET_PM_PATTERN_FILTER 0x42
#define USB_CDC_SET_ETHERNET_PACKET_FILTER 0x43
#define USB_CDC_GET_ETHERNET_STATISTIC 0x44
/* Line Coding Structure from CDC spec 6.2.13 */
struct usb_cdc_line_coding {
uint32_t dwDTERate;
uint8_t bCharFormat;
#define USB_CDC_1_STOP_BITS 0
#define USB_CDC_1_5_STOP_BITS 1
#define USB_CDC_2_STOP_BITS 2
uint8_t bParityType;
#define USB_CDC_NO_PARITY 0
#define USB_CDC_ODD_PARITY 1
#define USB_CDC_EVEN_PARITY 2
#define USB_CDC_MARK_PARITY 3
#define USB_CDC_SPACE_PARITY 4
uint8_t bDataBits;
} __attribute__ ((packed));
/* table 62; bits in multicast filter */
#define USB_CDC_PACKET_TYPE_PROMISCUOUS (1 << 0)
#define USB_CDC_PACKET_TYPE_ALL_MULTICAST (1 << 1) /* no filter */
#define USB_CDC_PACKET_TYPE_DIRECTED (1 << 2)
#define USB_CDC_PACKET_TYPE_BROADCAST (1 << 3)
#define USB_CDC_PACKET_TYPE_MULTICAST (1 << 4) /* filtered */
/*-------------------------------------------------------------------------*/
/*
* Class-Specific Notifications (6.3) sent by interrupt transfers
*
* section 3.8.2 table 11 of the CDC spec lists Ethernet notifications
* section 3.6.2.1 table 5 specifies ACM notifications, accepted by RNDIS
* RNDIS also defines its own bit-incompatible notifications
*/
#define USB_CDC_NOTIFY_NETWORK_CONNECTION 0x00
#define USB_CDC_NOTIFY_RESPONSE_AVAILABLE 0x01
#define USB_CDC_NOTIFY_SERIAL_STATE 0x20
#define USB_CDC_NOTIFY_SPEED_CHANGE 0x2a
struct usb_cdc_notification {
uint8_t bmRequestType;
uint8_t bNotificationType;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
#endif /*USB_CDC_H_*/

553
include/usb_ch9.h Normal file
View File

@ -0,0 +1,553 @@
#ifndef USB_CH9_H_
#define USB_CH9_H_
#include <stdint.h>
/*
* the content of this file comes from
* - linux/include/linux/usb/ch9.h
* with minor modifications:
* - type conversion (e.g. __u8 -> uint8_t)
* - usb_endpoint_descriptor: removed last 2 bytes
*/
/*-------------------------------------------------------------------------*/
/* CONTROL REQUEST SUPPORT */
/*
* USB directions
*
* This bit flag is used in endpoint descriptors' bEndpointAddress field.
* It's also one of three fields in control requests bRequestType.
*/
#define USB_DIR_OUT 0 /* to device */
#define USB_DIR_IN 0x80 /* to host */
/*
* USB types, the second of three bRequestType fields
*/
#define USB_TYPE_MASK (0x03 << 5)
#define USB_TYPE_STANDARD (0x00 << 5)
#define USB_TYPE_CLASS (0x01 << 5)
#define USB_TYPE_VENDOR (0x02 << 5)
#define USB_TYPE_RESERVED (0x03 << 5)
/*
* USB recipients, the third of three bRequestType fields
*/
#define USB_RECIP_MASK 0x1f
#define USB_RECIP_DEVICE 0x00
#define USB_RECIP_INTERFACE 0x01
#define USB_RECIP_ENDPOINT 0x02
#define USB_RECIP_OTHER 0x03
/* From Wireless USB 1.0 */
#define USB_RECIP_PORT 0x04
#define USB_RECIP_RPIPE 0x05
/*
* Standard requests, for the bRequest field of a SETUP packet.
*
* These are qualified by the bRequestType field, so that for example
* TYPE_CLASS or TYPE_VENDOR specific feature flags could be retrieved
* by a GET_STATUS request.
*/
#define USB_REQ_GET_STATUS 0x00
#define USB_REQ_CLEAR_FEATURE 0x01
#define USB_REQ_SET_FEATURE 0x03
#define USB_REQ_SET_ADDRESS 0x05
#define USB_REQ_GET_DESCRIPTOR 0x06
#define USB_REQ_SET_DESCRIPTOR 0x07
#define USB_REQ_GET_CONFIGURATION 0x08
#define USB_REQ_SET_CONFIGURATION 0x09
#define USB_REQ_GET_INTERFACE 0x0A
#define USB_REQ_SET_INTERFACE 0x0B
#define USB_REQ_SYNCH_FRAME 0x0C
#define USB_REQ_SET_ENCRYPTION 0x0D /* Wireless USB */
#define USB_REQ_GET_ENCRYPTION 0x0E
#define USB_REQ_RPIPE_ABORT 0x0E
#define USB_REQ_SET_HANDSHAKE 0x0F
#define USB_REQ_RPIPE_RESET 0x0F
#define USB_REQ_GET_HANDSHAKE 0x10
#define USB_REQ_SET_CONNECTION 0x11
#define USB_REQ_SET_SECURITY_DATA 0x12
#define USB_REQ_GET_SECURITY_DATA 0x13
#define USB_REQ_SET_WUSB_DATA 0x14
#define USB_REQ_LOOPBACK_DATA_WRITE 0x15
#define USB_REQ_LOOPBACK_DATA_READ 0x16
#define USB_REQ_SET_INTERFACE_DS 0x17
/*
* USB feature flags are written using USB_REQ_{CLEAR,SET}_FEATURE, and
* are read as a bit array returned by USB_REQ_GET_STATUS. (So there
* are at most sixteen features of each type.)
*/
#define USB_DEVICE_SELF_POWERED 0 /* (read only) */
#define USB_DEVICE_REMOTE_WAKEUP 1 /* dev may initiate wakeup */
#define USB_DEVICE_TEST_MODE 2 /* (wired high speed only) */
#define USB_DEVICE_BATTERY 2 /* (wireless) */
#define USB_DEVICE_B_HNP_ENABLE 3 /* (otg) dev may initiate HNP */
#define USB_DEVICE_WUSB_DEVICE 3 /* (wireless)*/
#define USB_DEVICE_A_HNP_SUPPORT 4 /* (otg) RH port supports HNP */
#define USB_DEVICE_A_ALT_HNP_SUPPORT 5 /* (otg) other RH port does */
#define USB_DEVICE_DEBUG_MODE 6 /* (special devices only) */
#define USB_ENDPOINT_HALT 0 /* IN/OUT will STALL */
/**
* struct usb_ctrlrequest - SETUP data for a USB device control request
* @bRequestType: matches the USB bmRequestType field
* @bRequest: matches the USB bRequest field
* @wValue: matches the USB wValue field (le16 byte order)
* @wIndex: matches the USB wIndex field (le16 byte order)
* @wLength: matches the USB wLength field (le16 byte order)
*
* This structure is used to send control requests to a USB device. It matches
* the different fields of the USB 2.0 Spec section 9.3, table 9-2. See the
* USB spec for a fuller description of the different fields, and what they are
* used for.
*
* Note that the driver for any interface can issue control requests.
* For most devices, interfaces don't coordinate with each other, so
* such requests may be made at any time.
*/
struct usb_ctrlrequest {
uint8_t bRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
/*
* STANDARD DESCRIPTORS ... as returned by GET_DESCRIPTOR, or
* (rarely) accepted by SET_DESCRIPTOR.
*
* Note that all multi-byte values here are encoded in little endian
* byte order "on the wire". But when exposed through Linux-USB APIs,
* they've been converted to cpu byte order.
*/
/*
* Descriptor types ... USB 2.0 spec table 9.5
*/
#define USB_DT_DEVICE 0x01
#define USB_DT_CONFIG 0x02
#define USB_DT_STRING 0x03
#define USB_DT_INTERFACE 0x04
#define USB_DT_ENDPOINT 0x05
#define USB_DT_DEVICE_QUALIFIER 0x06
#define USB_DT_OTHER_SPEED_CONFIG 0x07
#define USB_DT_INTERFACE_POWER 0x08
/* these are from a minor usb 2.0 revision (ECN) */
#define USB_DT_OTG 0x09
#define USB_DT_DEBUG 0x0a
#define USB_DT_INTERFACE_ASSOCIATION 0x0b
/* these are from the Wireless USB spec */
#define USB_DT_SECURITY 0x0c
#define USB_DT_KEY 0x0d
#define USB_DT_ENCRYPTION_TYPE 0x0e
#define USB_DT_BOS 0x0f
#define USB_DT_DEVICE_CAPABILITY 0x10
#define USB_DT_WIRELESS_ENDPOINT_COMP 0x11
#define USB_DT_WIRE_ADAPTER 0x21
#define USB_DT_RPIPE 0x22
/* Conventional codes for class-specific descriptors. The convention is
* defined in the USB "Common Class" Spec (3.11). Individual class specs
* are authoritative for their usage, not the "common class" writeup.
*/
#define USB_DT_CS_DEVICE (USB_TYPE_CLASS | USB_DT_DEVICE)
#define USB_DT_CS_CONFIG (USB_TYPE_CLASS | USB_DT_CONFIG)
#define USB_DT_CS_STRING (USB_TYPE_CLASS | USB_DT_STRING)
#define USB_DT_CS_INTERFACE (USB_TYPE_CLASS | USB_DT_INTERFACE)
#define USB_DT_CS_ENDPOINT (USB_TYPE_CLASS | USB_DT_ENDPOINT)
/* All standard descriptors have these 2 fields at the beginning */
struct usb_descriptor_header {
uint8_t bLength;
uint8_t bDescriptorType;
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_DEVICE: Device descriptor */
struct usb_device_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bcdUSB;
uint8_t bDeviceClass;
uint8_t bDeviceSubClass;
uint8_t bDeviceProtocol;
uint8_t bMaxPacketSize0;
uint16_t idVendor;
uint16_t idProduct;
uint16_t bcdDevice;
uint8_t iManufacturer;
uint8_t iProduct;
uint8_t iSerialNumber;
uint8_t bNumConfigurations;
} __attribute__ ((packed));
#define USB_DT_DEVICE_SIZE 18
/*
* Device and/or Interface Class codes
* as found in bDeviceClass or bInterfaceClass
* and defined by www.usb.org documents
*/
#define USB_CLASS_PER_INTERFACE 0 /* for DeviceClass */
#define USB_CLASS_AUDIO 1
#define USB_CLASS_COMM 2
#define USB_CLASS_HID 3
#define USB_CLASS_PHYSICAL 5
#define USB_CLASS_STILL_IMAGE 6
#define USB_CLASS_PRINTER 7
#define USB_CLASS_MASS_STORAGE 8
#define USB_CLASS_HUB 9
#define USB_CLASS_CDC_DATA 0x0a
#define USB_CLASS_CSCID 0x0b /* chip+ smart card */
#define USB_CLASS_CONTENT_SEC 0x0d /* content security */
#define USB_CLASS_VIDEO 0x0e
#define USB_CLASS_WIRELESS_CONTROLLER 0xe0
#define USB_CLASS_MISC 0xef
#define USB_CLASS_APP_SPEC 0xfe
#define USB_CLASS_VENDOR_SPEC 0xff
/*-------------------------------------------------------------------------*/
/* USB_DT_CONFIG: Configuration descriptor information.
*
* USB_DT_OTHER_SPEED_CONFIG is the same descriptor, except that the
* descriptor type is different. Highspeed-capable devices can look
* different depending on what speed they're currently running. Only
* devices with a USB_DT_DEVICE_QUALIFIER have any OTHER_SPEED_CONFIG
* descriptors.
*/
struct usb_config_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumInterfaces;
uint8_t bConfigurationValue;
uint8_t iConfiguration;
uint8_t bmAttributes;
uint8_t bMaxPower;
} __attribute__ ((packed));
#define USB_DT_CONFIG_SIZE 9
/* from config descriptor bmAttributes */
#define USB_CONFIG_ATT_ONE (1 << 7) /* must be set */
#define USB_CONFIG_ATT_SELFPOWER (1 << 6) /* self powered */
#define USB_CONFIG_ATT_WAKEUP (1 << 5) /* can wakeup */
#define USB_CONFIG_ATT_BATTERY (1 << 4) /* battery powered */
/*-------------------------------------------------------------------------*/
/* USB_DT_STRING: String descriptor */
struct usb_string_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wData[1]; /* UTF-16LE encoded */
} __attribute__ ((packed));
/* note that "string" zero is special, it holds language codes that
* the device supports, not Unicode characters.
*/
/*-------------------------------------------------------------------------*/
/* USB_DT_INTERFACE: Interface descriptor */
struct usb_interface_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bInterfaceNumber;
uint8_t bAlternateSetting;
uint8_t bNumEndpoints;
uint8_t bInterfaceClass;
uint8_t bInterfaceSubClass;
uint8_t bInterfaceProtocol;
uint8_t iInterface;
} __attribute__ ((packed));
#define USB_DT_INTERFACE_SIZE 9
/*-------------------------------------------------------------------------*/
/* USB_DT_ENDPOINT: Endpoint descriptor */
struct usb_endpoint_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
/* NOTE: these two are _only_ in audio endpoints. */
/* use USB_DT_ENDPOINT*_SIZE in bLength, not sizeof. */
// uint8_t bRefresh;
// uint8_t bSynchAddress;
} __attribute__ ((packed));
#define USB_DT_ENDPOINT_SIZE 7
//#define USB_DT_ENDPOINT_AUDIO_SIZE 9 /* Audio extension */
/*
* Endpoints
*/
#define USB_ENDPOINT_NUMBER_MASK 0x0f /* in bEndpointAddress */
#define USB_ENDPOINT_DIR_MASK 0x80
#define USB_ENDPOINT_XFERTYPE_MASK 0x03 /* in bmAttributes */
#define USB_ENDPOINT_XFER_CONTROL 0
#define USB_ENDPOINT_XFER_ISOC 1
#define USB_ENDPOINT_XFER_BULK 2
#define USB_ENDPOINT_XFER_INT 3
#define USB_ENDPOINT_MAX_ADJUSTABLE 0x80
/*-------------------------------------------------------------------------*/
/* USB_DT_DEVICE_QUALIFIER: Device Qualifier descriptor */
struct usb_qualifier_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bcdUSB;
uint8_t bDeviceClass;
uint8_t bDeviceSubClass;
uint8_t bDeviceProtocol;
uint8_t bMaxPacketSize0;
uint8_t bNumConfigurations;
uint8_t bRESERVED;
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_OTG (from OTG 1.0a supplement) */
struct usb_otg_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bmAttributes; /* support for HNP, SRP, etc */
} __attribute__ ((packed));
/* from usb_otg_descriptor.bmAttributes */
#define USB_OTG_SRP (1 << 0)
#define USB_OTG_HNP (1 << 1) /* swap host/device roles */
/*-------------------------------------------------------------------------*/
/* USB_DT_DEBUG: for special highspeed devices, replacing serial console */
struct usb_debug_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
/* bulk endpoints with 8 byte maxpacket */
uint8_t bDebugInEndpoint;
uint8_t bDebugOutEndpoint;
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_INTERFACE_ASSOCIATION: groups interfaces */
struct usb_interface_assoc_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bFirstInterface;
uint8_t bInterfaceCount;
uint8_t bFunctionClass;
uint8_t bFunctionSubClass;
uint8_t bFunctionProtocol;
uint8_t iFunction;
} __attribute__ ((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_SECURITY: group of wireless security descriptors, including
* encryption types available for setting up a CC/association.
*/
struct usb_security_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumEncryptionTypes;
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_KEY: used with {GET,SET}_SECURITY_DATA; only public keys
* may be retrieved.
*/
struct usb_key_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t tTKID[3];
uint8_t bReserved;
uint8_t bKeyData[0];
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_ENCRYPTION_TYPE: bundled in DT_SECURITY groups */
struct usb_encryption_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEncryptionType;
#define USB_ENC_TYPE_UNSECURE 0
#define USB_ENC_TYPE_WIRED 1 /* non-wireless mode */
#define USB_ENC_TYPE_CCM_1 2 /* aes128/cbc session */
#define USB_ENC_TYPE_RSA_1 3 /* rsa3072/sha1 auth */
uint8_t bEncryptionValue; /* use in SET_ENCRYPTION */
uint8_t bAuthKeyIndex;
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_BOS: group of wireless capabilities */
struct usb_bos_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumDeviceCaps;
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_DEVICE_CAPABILITY: grouped with BOS */
struct usb_dev_cap_header {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
} __attribute__((packed));
#define USB_CAP_TYPE_WIRELESS_USB 1
struct usb_wireless_cap_descriptor { /* Ultra Wide Band */
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
uint8_t bmAttributes;
#define USB_WIRELESS_P2P_DRD (1 << 1)
#define USB_WIRELESS_BEACON_MASK (3 << 2)
#define USB_WIRELESS_BEACON_SELF (1 << 2)
#define USB_WIRELESS_BEACON_DIRECTED (2 << 2)
#define USB_WIRELESS_BEACON_NONE (3 << 2)
uint16_t wPHYRates; /* bit rates, Mbps */
#define USB_WIRELESS_PHY_53 (1 << 0) /* always set */
#define USB_WIRELESS_PHY_80 (1 << 1)
#define USB_WIRELESS_PHY_107 (1 << 2) /* always set */
#define USB_WIRELESS_PHY_160 (1 << 3)
#define USB_WIRELESS_PHY_200 (1 << 4) /* always set */
#define USB_WIRELESS_PHY_320 (1 << 5)
#define USB_WIRELESS_PHY_400 (1 << 6)
#define USB_WIRELESS_PHY_480 (1 << 7)
uint8_t bmTFITXPowerInfo; /* TFI power levels */
uint8_t bmFFITXPowerInfo; /* FFI power levels */
uint16_t bmBandGroup;
uint8_t bReserved;
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_DT_WIRELESS_ENDPOINT_COMP: companion descriptor associated with
* each endpoint descriptor for a wireless device
*/
struct usb_wireless_ep_comp_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bMaxBurst;
uint8_t bMaxSequence;
uint16_t wMaxStreamDelay;
uint16_t wOverTheAirPacketSize;
uint8_t bOverTheAirInterval;
uint8_t bmCompAttributes;
#define USB_ENDPOINT_SWITCH_MASK 0x03 /* in bmCompAttributes */
#define USB_ENDPOINT_SWITCH_NO 0
#define USB_ENDPOINT_SWITCH_SWITCH 1
#define USB_ENDPOINT_SWITCH_SCALE 2
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_REQ_SET_HANDSHAKE is a four-way handshake used between a wireless
* host and a device for connection set up, mutual authentication, and
* exchanging short lived session keys. The handshake depends on a CC.
*/
struct usb_handshake {
uint8_t bMessageNumber;
uint8_t bStatus;
uint8_t tTKID[3];
uint8_t bReserved;
uint8_t CDID[16];
uint8_t nonce[16];
uint8_t MIC[8];
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB_REQ_SET_CONNECTION modifies or revokes a connection context (CC).
* A CC may also be set up using non-wireless secure channels (including
* wired USB!), and some devices may support CCs with multiple hosts.
*/
struct usb_connection_context {
uint8_t CHID[16]; /* persistent host id */
uint8_t CDID[16]; /* device id (unique w/in host context) */
uint8_t CK[16]; /* connection key */
} __attribute__((packed));
/*-------------------------------------------------------------------------*/
/* USB 2.0 defines three speeds, here's how Linux identifies them */
enum usb_device_speed {
USB_SPEED_UNKNOWN = 0, /* enumerating */
USB_SPEED_LOW, USB_SPEED_FULL, /* usb 1.1 */
USB_SPEED_HIGH, /* usb 2.0 */
USB_SPEED_VARIABLE, /* wireless (usb 2.5) */
};
enum usb_device_state {
/* NOTATTACHED isn't in the USB spec, and this state acts
* the same as ATTACHED ... but it's clearer this way.
*/
USB_STATE_NOTATTACHED = 0,
/* chapter 9 and authentication (wireless) device states */
USB_STATE_ATTACHED,
USB_STATE_POWERED, /* wired */
USB_STATE_UNAUTHENTICATED, /* auth */
USB_STATE_RECONNECTING, /* auth */
USB_STATE_DEFAULT, /* limited function */
USB_STATE_ADDRESS,
USB_STATE_CONFIGURED, /* most functions */
USB_STATE_SUSPENDED
/* NOTE: there are actually four different SUSPENDED
* states, returning to POWERED, DEFAULT, ADDRESS, or
* CONFIGURED respectively when SOF tokens flow again.
*/
};
#endif /*USB_CH9_H_*/

73
include/usb_dfu.h Normal file
View File

@ -0,0 +1,73 @@
#ifndef USB_DFU_H_
#define USB_DFU_H_
#include <stdint.h>
#include "usb_ch9.h"
#define USB_DT_DFU USB_DT_CS_DEVICE
/* DFU Descriptor Type */
#define USB_TYPE_DFU (USB_TYPE_CLASS | USB_RECIP_INTERFACE)
struct usb_dfu_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bmAttributes;
uint16_t wDetachTimeOut;
uint16_t wTransferSize;
uint16_t bcdDFUVersion;
} __attribute__ ((packed));
#define USB_DFU_CAN_DOWNLOAD 0x01
#define USB_DFU_CAN_UPLOAD 0x02
#define USB_DFU_MANIFEST_TOL 0x04
#define USB_DFU_WILL_DETACH 0x08
/* DFU class-specific requests (Section 3, DFU Rev 1.1) */
#define USB_REQ_DFU_DETACH 0x00
#define USB_REQ_DFU_DNLOAD 0x01
#define USB_REQ_DFU_UPLOAD 0x02
#define USB_REQ_DFU_GETSTATUS 0x03
#define USB_REQ_DFU_CLRSTATUS 0x04
#define USB_REQ_DFU_GETSTATE 0x05
#define USB_REQ_DFU_ABORT 0x06
struct dfu_status {
uint8_t bStatus;
uint8_t bwPollTimeout[3];
uint8_t bState;
uint8_t iString;
} __attribute__((packed));
#define DFU_STATUS_OK 0x00
#define DFU_STATUS_errTARGET 0x01
#define DFU_STATUS_errFILE 0x02
#define DFU_STATUS_errWRITE 0x03
#define DFU_STATUS_errERASE 0x04
#define DFU_STATUS_errCHECK_ERASED 0x05
#define DFU_STATUS_errPROG 0x06
#define DFU_STATUS_errVERIFY 0x07
#define DFU_STATUS_errADDRESS 0x08
#define DFU_STATUS_errNOTDONE 0x09
#define DFU_STATUS_errFIRMWARE 0x0a
#define DFU_STATUS_errVENDOR 0x0b
#define DFU_STATUS_errUSBR 0x0c
#define DFU_STATUS_errPOR 0x0d
#define DFU_STATUS_errUNKNOWN 0x0e
#define DFU_STATUS_errSTALLEDPKT 0x0f
enum dfu_state {
DFU_STATE_appIDLE = 0,
DFU_STATE_appDETACH = 1,
DFU_STATE_dfuIDLE = 2,
DFU_STATE_dfuDNLOAD_SYNC = 3,
DFU_STATE_dfuDNBUSY = 4,
DFU_STATE_dfuDNLOAD_IDLE = 5,
DFU_STATE_dfuMANIFEST_SYNC = 6,
DFU_STATE_dfuMANIFEST = 7,
DFU_STATE_dfuMANIFEST_WAIT_RST = 8,
DFU_STATE_dfuUPLOAD_IDLE = 9,
DFU_STATE_dfuERROR = 10,
};
#endif /*USB_DFU_H_*/

81
ldscript.ld Normal file
View File

@ -0,0 +1,81 @@
MEMORY
{
CODE (rx) : ORIGIN = 0x00100000, LENGTH = 256k
DATA (rwx) : ORIGIN = 0x00200000, LENGTH = 64k
}
SECTIONS
{
. = ORIGIN(CODE);
.text : {
*at91_init0.o (.text)
*at91_init1.o (.text)
*(.text)
*(.glue_7t)
*(.glue_7)
. = ALIGN(4);
_pio_isr_table = .;
*(.pio_isr)
_pio_isr_table_end = .;
. = ALIGN(4);
*(.rodata)
*(.rodata.*)
__text_end__ = .;
} >CODE =0
.data : AT (ADDR(.text) + SIZEOF(.text)) {
*(.data)
} >DATA =0
__data_start__ = ADDR(.data);
__data_end__ = ADDR(.data) + SIZEOF(.data);
.bss : {
*(.bss)
*(COMMON)
}
__bss_start__ = ADDR(.bss);
__bss_end__ = ADDR(.bss) + SIZEOF(.bss);
__stack_top__ = ORIGIN(DATA) + LENGTH(DATA);
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}

98
main.c Normal file
View File

@ -0,0 +1,98 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "AT91SAM7S256.h"
#include "at91_sysc.h"
#include "at91_dbgu.h"
#include "at91_pitc.h"
#include "at91_tests.h"
#include "at91_udp.h"
#include "at91_pio.h"
#include "at91_twi.h"
#include "at91_tc1.h"
#include "static_alloc.h"
#include "board.h"
#include <stdio.h>
#include <string.h>
AT91S_AIC *aic = AT91C_BASE_AIC;
AT91S_TWI *twi = AT91C_BASE_TWI;
AT91S_UDP *udp = AT91C_BASE_UDP;
static uint32_t pitc_test(struct pitc_timer *timer)
{
static uint32_t i;
*AT91C_PIOA_SODR = i;
i = i ^ LED_GREEN;
*AT91C_PIOA_CODR = i;
/*
struct rc_values rc;
uint32_t valid = rc_ppm_getvalues(&rc);
if (!valid)
rc.count = 0;
printf("%d channels: ", rc.count);
uint32_t j;
for (j = 0; j < rc.count; j++)
printf("%+3d ", rc.ch[j]);
printf("\n\r");
*/
return 0;
}
int main(void)
{
/* trigger pinchange-isrs */
at91_pio_init();
/* LED outputs */
*AT91C_PIOA_PER = LED_GREEN | LED_ORANGE;
*AT91C_PIOA_OER = LED_GREEN | LED_ORANGE;
/* needed for dbgu */
at91_sysc_init();
at91_dbgu_init();
at91_dbgu_puts("==========================================================\n\rGood morning Dave\n\r");
/* timer */
at91_pitc_init();
at91_rttc_test_init();
at91_tc1_init();
/* adc, need timer */
at91_adc_test_init();
/* twi */
at91_twi_init();
/* usb */
at91_udp_init();
struct pitc_timer *pitc_test_timer = alloc_pitc_timer(10, &pitc_test, NULL);
pitc_schedule_timer(pitc_test_timer);
printf("static alloc: %5ld bytes\n\r", static_alloc_used());
at91_twi_test();
while (1);
}

19
scripts/download.sh Executable file
View File

@ -0,0 +1,19 @@
#!/bin/bash
echo -e "
sleep 10
reset halt
wait_halt
mww 0xfffffd08 0xa5000001
sleep 10
arm7_9 sw_bkpts disable
arm7_9 force_hw_bkpts enable
arm7_9 dcc_downloads enable
sleep 10
flash probe 0
flash info 0
flash auto_erase on
flash write_image build/sam7fc.elf
sleep 10
reset run
exit" | nc localhost 4444

23
scripts/gdb-thumb.cfg Normal file
View File

@ -0,0 +1,23 @@
target remote localhost:3333
# Peripheral reset (also resets memory map)
#monitor mww 0xfffffd00 0xa5000002
#monitor sleep 10
# Enable User reset (via jtag trst)
monitor mww 0xfffffd08 0xa5000001
monitor sleep 10
monitor reset halt
monitor wait_halt
monitor arm7_9 sw_bkpts disable
monitor arm7_9 force_hw_bkpts enable
#monitor arm7_9 fast_memory_access enable
monitor arm7_9 dcc_downloads enable
monitor flash probe 0
monitor flash info 0
monitor flash auto_erase on
monitor flash write_image Debug_thumb/FlightCtrl_arm7.elf

23
scripts/gdb.cfg Normal file
View File

@ -0,0 +1,23 @@
target remote localhost:3333
# Peripheral reset (also resets memory map)
#monitor mww 0xfffffd00 0xa5000002
#monitor sleep 10
# Enable User reset (via jtag trst)
monitor mww 0xfffffd08 0xa5000001
monitor sleep 10
monitor reset halt
monitor wait_halt
monitor arm7_9 sw_bkpts disable
monitor arm7_9 force_hw_bkpts enable
#monitor arm7_9 fast_memory_access enable
monitor arm7_9 dcc_downloads enable
monitor flash probe 0
monitor flash info 0
monitor flash auto_erase on
monitor flash write_image Debug/FlightCtrl_arm7.elf

16
scripts/openocd.cfg Normal file
View File

@ -0,0 +1,16 @@
telnet_port 4444
gdb_port 3333
daemon_startup reset
interface parport
parport_port 0
parport_cable wiggler
jtag_speed 0
reset_config srst_only
jtag_device 4 0x1 0xf 0xe
#jtag_nsrst_delay 500
#jtag_ntrst_delay 100
target arm7tdmi little reset_halt 0 arm7tdmi
flash bank at91sam7 0 0 0 0 0

99
src/at91_adc.c Normal file
View File

@ -0,0 +1,99 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "board.h"
#include "at91_pitc.h"
#include "static_alloc.h"
static uint16_t adc_result[4];
static void at91_adc_isr(void)
{
AT91S_PDC *pdc = AT91C_BASE_PDC_ADC;
pdc->PDC_RPR = (uint32_t) &adc_result;
pdc->PDC_RCR = ARRAY_SIZE(adc_result);
pdc->PDC_PTCR = AT91C_PDC_RXTEN;
/* clear interrupts */
AT91S_ADC *adc = AT91C_BASE_ADC;
uint32_t status = adc->ADC_SR;
status = status;
}
static uint32_t adc_trigger(struct pitc_timer *timer)
{
*AT91C_ADC_CR = AT91C_ADC_START;
return PITC_RESTART_TIMER;
}
void at91_adc_test_init(void)
{
/* enable ADC clock */
*AT91C_PMC_PCER = (1 << AT91C_ID_ADC);
/* ADC Software reset */
AT91S_ADC *adc = AT91C_BASE_ADC;
adc->ADC_CR = AT91C_ADC_SWRST;
/*
* ADC config: 10bit, no sleep
* 4.8MHz (48MHz / ((4 +1) * 2) = 4.8MHz)
* 96 cycles Startup ((11 +1) * 8 / 4.8MHz = 20us)
* 3 cycles SH ((2 +1) / 4.8MHz = 625ns)
* Conversion time per channel @5MHz ~2us
*/
adc->ADC_MR = AT91C_ADC_TRGEN_DIS |
AT91C_ADC_LOWRES_10_BIT |
AT91C_ADC_SLEEP_NORMAL_MODE |
(AT91C_ADC_PRESCAL & (4 << 8)) |
(AT91C_ADC_STARTUP & (11 << 16)) |
(AT91C_ADC_SHTIM & (2 << 24));
/* setup PDC */
AT91S_PDC *pdc = AT91C_BASE_PDC_ADC;
pdc->PDC_RPR = (uint32_t) &adc_result;
pdc->PDC_RCR = ARRAY_SIZE(adc_result);
pdc->PDC_PTCR = AT91C_PDC_RXTEN;
/* enable 4 channels, PDC Interrupt */
adc->ADC_CHER = 0xF0;
adc->ADC_IER = AT91C_ADC_ENDRX;
/* low priority, level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_ADC] = IRQPRIO_ADC | AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_ADC] = (uint32_t)at91_adc_isr;
aic->AIC_IECR = (1<<AT91C_ID_ADC);
/* schedule trigger */
struct pitc_timer *adc_timer = alloc_pitc_timer(100, &adc_trigger, NULL);
pitc_schedule_timer(adc_timer);
}
void at91_adc_printresults(void)
{
uint8_t i;
for (i = 0; i < ARRAY_SIZE(adc_result); i++)
printf("%x:0x%03X ", i, adc_result[i]);
printf("\n");
}

90
src/at91_dbgu.c Normal file
View File

@ -0,0 +1,90 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include <string.h>
#include "AT91SAM7S256.h"
#include "board.h"
#include "at91_dbgu.h"
#include "at91_sysc.h"
#include "fifo.h"
static struct fifo *txfifo;
static void dbgu_isr(uint32_t status)
{
/* only enabled interrupts */
status &= *AT91C_DBGU_IMR;
/*
if (status & AT91C_US_TXEMPTY) {
static char c;
if (c == '\n') {
*AT91C_DBGU_THR = '\r';
c = 0;
} else if (fifo_getbyte(&txfifo, &c) == 1)
*AT91C_DBGU_THR = c;
else
*AT91C_DBGU_IDR = AT91C_US_TXEMPTY;
}
*/
if (status & AT91C_US_TXBUFE)
if (fifo_txpdc(txfifo, AT91C_BASE_PDC_DBGU, 16) == 0)
*AT91C_DBGU_IDR = AT91C_US_TXBUFE;
}
void at91_dbgu_init(void)
{
/* switch pins to UART */
*AT91C_PIOA_PDR = AT91C_PA9_DRXD | AT91C_PA10_DTXD;
/* enable Debug Port with 115200 Baud (+0.16%) */
AT91S_DBGU *dbgu = AT91C_BASE_DBGU;
dbgu->DBGU_BRGR = BAUD_TO_DIV(115200);
dbgu->DBGU_MR = AT91C_US_PAR_NONE | AT91C_US_CHMODE_NORMAL;
dbgu->DBGU_CR = AT91C_US_RXEN | AT91C_US_TXEN | AT91C_US_RSTSTA;
txfifo = fifo_alloc(1024);
/* enable TX PDC */
dbgu->DBGU_PTCR = AT91C_PDC_TXTEN;
sysc_register_isr(AT91_SYSIRQ_DBGU, dbgu_isr);
}
void at91_dbgu_putc(char c)
{
fifo_putbyte(txfifo, c);
// *AT91C_DBGU_IER = AT91C_US_TXEMPTY;
*AT91C_DBGU_IER = AT91C_US_TXBUFE;
}
void at91_dbgu_puts(const char *p)
{
fifo_put(txfifo, p, strlen(p));
// *AT91C_DBGU_IER = AT91C_US_TXEMPTY;
*AT91C_DBGU_IER = AT91C_US_TXBUFE;
}
int at91_dbgu_write(void *base, const char *buf, size_t len)
{
int retval = fifo_put(txfifo, buf, len);
// *AT91C_DBGU_IER = AT91C_US_TXEMPTY;
*AT91C_DBGU_IER = AT91C_US_TXBUFE;
return retval;
}

162
src/at91_exceptions.c Normal file
View File

@ -0,0 +1,162 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include "AT91SAM7S256.h"
#include "board.h"
static void dbgu_putchar(char c)
{
while (!(*AT91C_DBGU_CSR & AT91C_US_TXEMPTY));
*AT91C_DBGU_THR = c;
if (c == '\n') {
while (!(*AT91C_DBGU_CSR & AT91C_US_TXEMPTY));
*AT91C_DBGU_THR = '\r';
}
}
static void dbgu_puts(const char *p)
{
while (*p != '\0')
dbgu_putchar(*p++);
}
static void dbgu_hexvar(const char *name, uint32_t var)
{
dbgu_puts(name);
char buf[11];
buf[0] = '0';
buf[1] = 'x';
uint32_t i;
for (i = 9; i > 1; i--) {
buf[i] = (var & 0x0F);
buf[i] += (buf[i] < 0xa) ? '0' : ('a' - 0x0a);
var >>= 4;
}
buf[10] = '\0';
dbgu_puts(buf);
}
/*
ARM7TDMI 32bit Undefined Address Instruction Fetch Abort
(ASR:0x02020a01 AASR:0x80000008)
--- Registerdump (cpsr:0xa0000013 - SVC):
r0:0x00000002 r1:0x0000000c r2:0x00200038 r3:0x80000000
r4:0x0020fffc r5:0x00101788 r6:0x00000180 r7:0x41000000
r8:0x00008400 r9:0x00100004 r10:0x03000294 fp:0x0020fe84
r12:0x0020fe10 sp:0x0020fe70 lr:0x00102174 pc:0x80000004
--- Stackdump:
0x0020fe70: 0x0020fe7c 0x00101648 0x001015a8 0x0020feaf
0x0020fe80: 0x0020fec0 0x0020fe90 0x00101780 0x00101620
0x0020fe90: 0x00000002 0x00000000 0x00000030 0x00000000
0x0020fea0: 0x001029a8 0x307830b0 0x33383730 0x00303337
*/
void at91_abt_handler(uint32_t cpsr, uint32_t *registers)
{
/* enable Debug Port with 115200 Baud (+0.16%) */
AT91S_DBGU *dbgu = AT91C_BASE_DBGU;
dbgu->DBGU_BRGR = BAUD_TO_DIV(115200);
dbgu->DBGU_MR = AT91C_US_PAR_NONE | AT91C_US_CHMODE_NORMAL;
dbgu->DBGU_CR = AT91C_US_RXEN | AT91C_US_TXEN | AT91C_US_RSTSTA;
/* switch pins to UART */
*AT91C_PIOA_PDR = AT91C_PA9_DRXD | AT91C_PA10_DTXD;
AT91_REG asr = *AT91C_MC_ASR;
if (asr & AT91C_MC_MST0)
dbgu_puts("PDC ");
else if (asr & AT91C_MC_MST1)
dbgu_puts("ARM7TDMI ");
switch (asr & AT91C_MC_ABTSZ) {
case AT91C_MC_ABTSZ_BYTE:
dbgu_puts("8bit ");
break;
case AT91C_MC_ABTSZ_HWORD:
dbgu_puts("16bit ");
break;
case AT91C_MC_ABTSZ_WORD:
dbgu_puts("32bit ");
break;
}
if (asr & AT91C_MC_UNDADD)
dbgu_puts("Undefined Address ");
else if (asr & AT91C_MC_MISADD)
dbgu_puts("Misaliged Address ");
switch (asr & AT91C_MC_ABTTYP) {
case AT91C_MC_ABTTYP_DATAR:
dbgu_puts("Data Read ");
break;
case AT91C_MC_ABTTYP_DATAW:
dbgu_puts("Data Write ");
break;
case AT91C_MC_ABTTYP_FETCH:
dbgu_puts("Prefetch ");
break;
}
dbgu_hexvar("Abort\n(ASR:", asr);
dbgu_hexvar(" AASR:", *AT91C_MC_AASR);
dbgu_puts(")\n");
dbgu_hexvar("--- Registerdump (cpsr:", cpsr);
dbgu_puts(" - ");
switch (cpsr & 0x1F) {
case 0x10: dbgu_puts("USR"); break;
case 0x11: dbgu_puts("FIQ"); break;
case 0x12: dbgu_puts("IRQ"); break;
case 0x13: dbgu_puts("SVC"); break;
case 0x17: dbgu_puts("ABT"); break;
case 0x1B: dbgu_puts("UND"); break;
case 0x1F: dbgu_puts("SYS"); break;
}
dbgu_hexvar("):\n r0:", registers[3]);
dbgu_hexvar(" r1:", registers[4]);
dbgu_hexvar(" r2:", registers[5]);
dbgu_hexvar(" r3:", registers[6]);
dbgu_hexvar("\n r4:", registers[7]);
dbgu_hexvar(" r5:", registers[8]);
dbgu_hexvar(" r6:", registers[9]);
dbgu_hexvar(" r7:", registers[10]);
dbgu_hexvar("\n r8:", registers[11]);
dbgu_hexvar(" r9:", registers[12]);
dbgu_hexvar(" r10:", registers[13]);
dbgu_hexvar(" fp:", registers[14]);
dbgu_hexvar("\nr12:", registers[15]);
dbgu_hexvar(" sp:", registers[0]);
dbgu_hexvar(" lr:", registers[1]);
dbgu_hexvar(" pc:", registers[2]);
dbgu_puts("\n--- Stackdump:");
uint32_t *val = (uint32_t *)(registers[0] & ~0x0F);
for ( ; val < (uint32_t *)(registers[0] & ~0x0F) +16; val++) {
if (!((uint32_t)val & 0x0F)) {
dbgu_hexvar("\n", (uint32_t)val);
dbgu_putchar(':');
}
dbgu_hexvar(" ", *val);
}
dbgu_putchar('\n');
}

69
src/at91_pio.c Normal file
View File

@ -0,0 +1,69 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "board.h"
#include "at91_pio.h"
/* extern symbols, defined in ldscript */
extern struct pio_pinchange_isr _pio_isr_table;
extern struct pio_pinchange_isr _pio_isr_table_end;
static void pio_isr(void)
{
uint32_t status = *AT91C_PIOA_ISR;
uint32_t input = *AT91C_PIOA_PDSR;
struct pio_pinchange_isr *isr;
for (isr = &_pio_isr_table; isr < &_pio_isr_table_end; isr++)
if (isr->mask & status)
isr->func(status, input);
}
void pio_trigger_isr(uint32_t mask)
{
uint32_t input = *AT91C_PIOA_PDSR;
struct pio_pinchange_isr *isr;
for (isr = &_pio_isr_table; isr < &_pio_isr_table_end; isr++)
if (isr->mask & mask)
isr->func(mask, input);
}
void at91_pio_init(void)
{
/* enable PIO clock */
*AT91C_PMC_PCER = (1 << AT91C_ID_PIOA);
/* enable pinchange interrupts */
struct pio_pinchange_isr *isr;
for (isr = &_pio_isr_table; isr < &_pio_isr_table_end; isr++)
*AT91C_PIOA_IER = isr->mask;
/* dummy read to clear interrupts */
uint32_t dummy = *AT91C_PIOA_ISR;
dummy = dummy;
/* low priority, level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_PIOA] = IRQPRIO_PIOA | AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_PIOA] = (uint32_t)pio_isr;
aic->AIC_IECR = (1 << AT91C_ID_PIOA);
}

90
src/at91_pitc.c Normal file
View File

@ -0,0 +1,90 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "AT91SAM7S256.h"
#include "at91_pitc.h"
#include "at91_sysc.h"
#include "board.h"
#include "static_alloc.h"
/* PIV is 20bit -> min. 3Hz @48MHz MCK */
#define HZ_TO_PIV(HZ) (MCK / (16 * HZ))
static LIST_HEAD(timer_list);
volatile static uint32_t pitc_ticks;
struct pitc_timer * alloc_pitc_timer(uint32_t interval, uint32_t (*func)(struct pitc_timer *), void *privdata)
{
struct pitc_timer *timer = static_alloc(sizeof(struct pitc_timer));
timer->interval = interval;
timer->func = func;
timer->privdata = privdata;
return timer;
}
void pitc_schedule_timer(struct pitc_timer *timer)
{
timer->nextrun = timer->interval + pitc_ticks;
struct pitc_timer *search;
list_for_each_entry(search, &timer_list, list)
if (search->nextrun > timer->nextrun)
break;
list_add_tail(&timer->list, &search->list);
}
static void pitc_isr(uint32_t status)
{
/* get Ticks and clear interrupt */
pitc_ticks += (*AT91C_PITC_PIVR & AT91C_PITC_PICNT) >> 20;
struct pitc_timer *search, *tmp;
list_for_each_entry_safe(search, tmp, &timer_list, list) {
/* if this entry not scheduled yet, abort search */
if (pitc_ticks < search->nextrun)
break;
/* remove from list */
list_del(&search->list);
/* exec handler */
if (search->func(search) == PITC_REMOVE_TIMER) {
/* one-shot timer, mark as completed */
search->nextrun = 0x00;
continue;
}
/* interval timer, reschedule it */
pitc_schedule_timer(search);
}
}
uint32_t pitc_get_ticks(void)
{
return pitc_ticks;
}
void at91_pitc_init(void)
{
sysc_register_isr(AT91_SYSIRQ_PIT, &pitc_isr);
*AT91C_PITC_PIMR = (AT91C_PITC_PIV & HZ_TO_PIV(100)) |
AT91C_PITC_PITEN |
AT91C_PITC_PITIEN;
}

34
src/at91_rttc_test.c Normal file
View File

@ -0,0 +1,34 @@
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "at91_sysc.h"
#include "board.h"
static void rtt_isr(uint32_t status)
{
*AT91C_RTTC_RTAR = *AT91C_RTTC_RTVR +1;
/*
static uint32_t i;
*AT91C_PIOA_SODR = i;
i = i ^ LED_ORANGE;
*AT91C_PIOA_CODR = i;
*/
}
void at91_rttc_test_init(void)
{
/* calculate SLOWCK from MAINCK and measured MAINF */
uint32_t prescaler = MAINCK * 16 / (*AT91C_CKGR_MCFR & AT91C_CKGR_MAINF);
sysc_register_isr(AT91_SYSIRQ_RTT, &rtt_isr);
/*
* AT91C_RTTC_RTTINCIEN doesn't work
* use AT91C_RTTC_ALMIEN and increment RTAR in isr
*/
*AT91C_RTTC_RTAR = *AT91C_RTTC_RTVR +1;
*AT91C_RTTC_RTMR = (AT91C_RTTC_RTPRES & prescaler) |
AT91C_RTTC_ALMIEN |
AT91C_RTTC_RTTRST;
printf("rttc running at %ld Hz\n\r", prescaler);
}

154
src/at91_sysc.c Normal file
View File

@ -0,0 +1,154 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "AT91SAM7S256.h"
#include "at91_sysc.h"
#include "board.h"
static SYSCISR *sysc_isrs[AT91_SYSIRQ_COUNT];
struct _irq_regs {
AT91_REG *mask_register;
uint32_t mask;
AT91_REG *status_register;
uint32_t status;
};
/* same IDs as sysc_isrs enum! */
static const struct _irq_regs irq_regs[] = {
/*
* PIT (Periodic Intervall Timer)
* ISR must read AT91C_PITC_PIVR to clear interrupt
* - PITIEN (Periodic Intervall Timer Interrupt Enable)
*/
{ AT91C_PITC_PIMR, AT91C_PITC_PITIEN,
AT91C_PITC_PISR, AT91C_PITC_PITS
},
/*
* DBGU (Debug Unit)
* TODO: must use AT91C_DBGU_IDR to fault disable interrupt
* - 12 Interrupt sources
*/
{ AT91C_DBGU_IMR, (AT91C_US_RXRDY | AT91C_US_TXRDY |
AT91C_US_ENDRX | AT91C_US_ENDTX |
AT91C_US_OVRE | AT91C_US_FRAME |
AT91C_US_PARE | AT91C_US_TXEMPTY |
AT91C_US_TXBUFE | AT91C_US_RXBUFF |
AT91C_US_COMM_TX | AT91C_US_COMM_RX),
AT91C_DBGU_CSR, (AT91C_US_RXRDY | AT91C_US_TXRDY |
AT91C_US_ENDRX | AT91C_US_ENDTX |
AT91C_US_OVRE | AT91C_US_FRAME |
AT91C_US_PARE | AT91C_US_TXEMPTY |
AT91C_US_TXBUFE | AT91C_US_RXBUFF |
AT91C_US_COMM_TX | AT91C_US_COMM_RX)
},
/*
* EFC (Embedded Flash Controller / Memory Controller)
*/
{ AT91C_MC_FMR, (AT91C_MC_FRDY | AT91C_MC_LOCKE | AT91C_MC_PROGE),
AT91C_MC_FSR, (AT91C_MC_FRDY | AT91C_MC_LOCKE | AT91C_MC_PROGE)
},
/*
* WDT (Watchdog Timer)
* WDMR can be written only once (no fault disable)
* - WDFIEN (Watchdog Fault Interrupt Enable)
*/
{ AT91C_WDTC_WDMR, AT91C_WDTC_WDFIEN,
AT91C_WDTC_WDSR, (AT91C_WDTC_WDUNF | AT91C_WDTC_WDERR)
},
/*
* RTT (Real-Time Timer)
* Interrupts must be disabled during ISR?!
* - ALMIEN (Alarm Interrupt Enable)
* - RTTCINCIEN (Real-Time Timer Increment Interrupt Enable)
*/
{ AT91C_RTTC_RTMR, (AT91C_RTTC_ALMIEN | AT91C_RTTC_RTTINCIEN),
AT91C_RTTC_RTSR, (AT91C_RTTC_ALMS | AT91C_RTTC_RTTINC)
},
/*
* RSTC (Reset Controller)
* - AT91C_RSTC_URSTIEN (User Reset Interrupt Enable)
* - AT91C_RSTC_BODIEN (Brownout Detection Interrupt Enable)
*/
{ AT91C_RSTC_RMR, (AT91C_RSTC_URSTIEN | AT91C_RSTC_BODIEN),
AT91C_RSTC_RSR, (AT91C_RSTC_URSTS | AT91C_RSTC_BODSTS)
},
/*
* PMC (Power Managment Controller)
* TODO: must use AT91C_PMC_IDR to fault disable interrupt
* - 6 Interrupt sources
*/
{ AT91C_PMC_IMR, (AT91C_PMC_MOSCS | AT91C_PMC_LOCK |
AT91C_PMC_MCKRDY | AT91C_PMC_PCK0RDY |
AT91C_PMC_PCK1RDY | AT91C_PMC_PCK2RDY),
AT91C_PMC_SR, (AT91C_PMC_MOSCS | AT91C_PMC_LOCK |
AT91C_PMC_MCKRDY | AT91C_PMC_PCK0RDY |
AT91C_PMC_PCK1RDY | AT91C_PMC_PCK2RDY)
},
};
/* check Interrupts from internal hardware */
static void at91_sysc_isr(void)
{
uint32_t id;
for (id = 0; id < AT91_SYSIRQ_COUNT; id++) {
/* check if interrups are enabled */
if (*(irq_regs[id].mask_register) & irq_regs[id].mask) {
/* check if interrupts are active */
uint32_t status = *(irq_regs[id].status_register);
if (status & irq_regs[id].status) {
/* execute handler */
if (sysc_isrs[id]) {
sysc_isrs[id](status);
} else {
/* disable interrupts */
*(irq_regs[id].mask_register) &= ~irq_regs[id].mask;
}
}
}
}
}
void at91_sysc_init(void)
{
/* high priority, level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_SYS] = IRQPRIO_SYSC |
AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_SYS] = (uint32_t)at91_sysc_isr;
aic->AIC_IECR = (1<<AT91C_ID_SYS);
}
void sysc_register_isr(enum syscirqs irq, SYSCISR *isr)
{
if (irq >= AT91_SYSIRQ_COUNT)
return;
sysc_isrs[irq] = isr;
}

110
src/at91_tc1.c Normal file
View File

@ -0,0 +1,110 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "board.h"
#include "at91_tc1.h"
#define ROUND_DIV256(x) ((x >> 8) + ((x & 0x80) ? 1 : 0))
static uint32_t ppm_arr[MAX_CHANNELS];
static uint32_t ch, cnt, valid;
static void ppm_isr(void)
{
/* RC Compare -> no TIOA1 edge for 2.5ms */
uint32_t status = *AT91C_TC1_SR;
if (status & AT91C_TC_CPCS) {
/* average channel count */
cnt = ((cnt * 7) + (ch << 8)) / 8;
/* at least 4 channels and a stable channel count */
valid = (ROUND_DIV256(cnt) == ch) && (ch >= 4);
/* reset index */
ch = 0;
}
/* edge on TIOA1 */
if (status & AT91C_TC_LDRAS) {
/* get impulse width */
uint16_t ra = *AT91C_TC1_RA;
/* valid range: 1 - 2ms */
if (ra > 0x0500 && ra < 0x0D00) {
if (ch < ARRAY_SIZE(ppm_arr))
ppm_arr[ch] = ((ppm_arr[ch] * 3) + ra) / 4;
ch++;
}
}
}
/*
struct cal_data {
uint16_t min;
uint16_t mid;
uint16_t max;
};
int16_t getval(struct cal_data *cal, uint16_t input)
{
int32_t x = (input - cal->mid) * 1024;
uint32_t y = (x > 0) ? (cal->max - cal->mid) : (cal->mid - cal->min);
return x / y;
}
*/
uint32_t rc_ppm_getvalues(struct rc_values *rc)
{
uint32_t i;
rc->count = MIN(ROUND_DIV256(cnt), ARRAY_SIZE(ppm_arr));
for (i = 0; i < rc->count; i++)
rc->ch[i] = (ppm_arr[i] - 0x8C0);
return valid;
}
void at91_tc1_init(void)
{
/* enable TC1 clock */
*AT91C_PMC_PCER = (1 << AT91C_ID_TC1);
/* MCK /32, trigger & capture on falling TIOA1 edge */
*AT91C_TC1_CMR = AT91C_TC_CLKS_TIMER_DIV3_CLOCK | AT91C_TC_LDRA_FALLING |
AT91C_TC_ETRGEDG_FALLING | AT91C_TC_ABETRG;
/* enable RA load and RC compare interrupt */
*AT91C_TC1_IER = AT91C_TC_LDRAS | AT91C_TC_CPCS;
/* RC Compare Interrupt if no rising Edge on TIOA1 for 2.56ms */
*AT91C_TC1_RC = 0x0F00;
/* enable & trigger the clock */
*AT91C_TC1_CCR = AT91C_TC_CLKEN | AT91C_TC_SWTRG;
/* level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_TC1] = IRQPRIO_TC1 | AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_TC1] = (uint32_t)ppm_isr;
aic->AIC_IECR = (1 << AT91C_ID_TC1);
}

241
src/at91_twi.c Normal file
View File

@ -0,0 +1,241 @@
/***************************************************************************
* Copyright (C) 02/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "board.h"
#include "at91_twi.h"
#include "at91_pio.h"
/*
* undocumented TWI_SR flags, at least OVRE seems to be present on a sam7s256
* taken from linux-2.6.24/include/asm-arm/arch-at91/at91_twi.h
*/
#define AT91_TWI_OVRE (1<<6) /* Overrun */
#define AT91_TWI_UNRE (1<<7) /* Underrun */
/*
* while ((cldiv = ((MCK / (2 * TWI)) -3) / (1 << ckdiv)) > 255)
* ckdiv++ ;
*
* works for TWI >= 100kHz
*/
#define TWI_CLK(x) (((MCK / (2 * (x))) -3)<<8 | ((MCK / (2 * (x))) -3))
enum twi_states {
TWI_IDLE = 0x00,
TWI_ERROR,
TWI_GENERIC_CMD = 0x10,
TWI_BLMC_UPDATE = 0x20,
};
static volatile uint32_t twi_state = TWI_IDLE;
static uint8_t *twi_data;
static uint32_t twi_size;
static uint32_t twi_count;
static void twi_isr(void)
{
/* get status */
uint32_t status = *AT91C_TWI_SR;
status &= *AT91C_TWI_IMR;
/* NACK - disable all interrupts and go to state TWI_ERROR */
if (status & AT91C_TWI_NACK) {
*AT91C_TWI_IDR = AT91C_TWI_TXCOMP | AT91C_TWI_RXRDY | AT91C_TWI_TXRDY | AT91C_TWI_NACK;
twi_state = TWI_ERROR;
// TODO: TWI_BLMC_UPDATE?
return;
}
/* tx register ready for new data */
if (status & AT91C_TWI_TXRDY) {
if (twi_count != twi_size) {
/* feed next byte */
*AT91C_TWI_THR = twi_data[twi_count++];
} else {
/* wait for TXCOMP */
*AT91C_TWI_IDR = AT91C_TWI_RXRDY | AT91C_TWI_TXRDY;
*AT91C_TWI_IER = AT91C_TWI_TXCOMP | AT91C_TWI_NACK;
}
}
/* rx register has data */
if (status & AT91C_TWI_RXRDY) {
/* get data */
twi_data[twi_count++] = *AT91C_TWI_RHR;
/* transfer complete? */
if (twi_count == twi_size) {
/* send STOP and wait for TXCOMP */
*AT91C_TWI_CR = AT91C_TWI_STOP;
*AT91C_TWI_IDR = AT91C_TWI_TXRDY;
*AT91C_TWI_IER = AT91C_TWI_TXCOMP | AT91C_TWI_NACK;
}
}
/* transfer really complete? */
if (status & AT91C_TWI_TXCOMP) {
/* are we doing a blmc update? */
if (twi_state == TWI_BLMC_UPDATE) {
uint32_t addr = (*AT91C_TWI_MMR >> 16) & 0x7F;
if (addr != TWI_ADDR_BL4) {
/* increase address */
*AT91C_TWI_MMR += (1<<16);
/* send next value to next blmc */
*AT91C_TWI_THR = *twi_data++;
} else {
// TODO:
}
} else {
*AT91C_TWI_IDR = AT91C_TWI_TXCOMP | AT91C_TWI_RXRDY | AT91C_TWI_TXRDY | AT91C_TWI_NACK;
twi_state = TWI_IDLE;
}
}
}
uint32_t twi_setpwm(uint8_t *values)
{
if (twi_state != TWI_IDLE)
return 1;
twi_state = TWI_BLMC_UPDATE;
twi_data = values; /* data is not copied! */
twi_size = 0;
twi_count = 0;
*AT91C_TWI_MMR = (TWI_ADDR_BL1 << 16) | AT91C_TWI_IADRSZ_1_BYTE;
*AT91C_TWI_IADR = CMD_SET_PWM;
*AT91C_TWI_THR = *twi_data++;
*AT91C_TWI_IER = AT91C_TWI_TXRDY | AT91C_TWI_NACK;
return 0;
}
uint32_t twi_cmd(uint8_t addr, struct blmc_cmd *cmd)
{
if (twi_state != TWI_IDLE)
return 1;
/* TODO: locking needed? */
twi_state = TWI_GENERIC_CMD;
/* read transfer, or write transfer with payload */
if (cmd->mode & BLMC_CMD_READ || cmd->size != 0) {
/* set address, direction, argument count and command bytes */
*AT91C_TWI_MMR = (addr << 16) | (cmd->mode & 0xFF) << 8;
*AT91C_TWI_IADR = cmd->cmd;
/* write transfer without payload */
} else {
/* use one cmd byte as payload (needed to start transfer) */
cmd->mode--;
*AT91C_TWI_MMR = (addr << 16) | (cmd->mode & 0xFF) << 8;
*AT91C_TWI_IADR = (cmd->cmd) >> 8;
}
/* isr needs data & size parameters */
twi_data = cmd->data;
twi_size = cmd->size;
twi_count = 0;
if (cmd->mode & BLMC_CMD_READ) {
*AT91C_TWI_CR = AT91C_TWI_START;
*AT91C_TWI_IER = AT91C_TWI_RXRDY | AT91C_TWI_NACK;
} else {
*AT91C_TWI_THR = (twi_size != 0) ? cmd->data[twi_count++] : (cmd->cmd & 0xFF);
*AT91C_TWI_IER = AT91C_TWI_TXRDY | AT91C_TWI_NACK;
}
/*
* wait for end
* TODO: locking needed?
* TODO: timeout?
*/
while (twi_state != TWI_IDLE && twi_state != TWI_ERROR);
if (twi_state != TWI_IDLE) {
twi_state = TWI_IDLE;
return 1;
}
return 0;
}
void at91_twi_test(void)
{
uint32_t i;
for (i = TWI_ADDR_BL1; i <= TWI_ADDR_BL4; i++) {
uint8_t buf[16];
struct blmc_cmd cmd = {
.cmd = CMD_GET_INFO,
.mode = BLMC_CMD_READ | BLMC_CMD_0_ARG,
.size = sizeof(buf),
.data = buf,
};
uint32_t retval = twi_cmd(i, &cmd);
printf("twi(0x%02lx): %ld '%s' ", i, retval, buf);
cmd.cmd = CMD_GET_SIGNATURE;
cmd.size = 4;
twi_cmd(i, &cmd);
printf("(sig: 0x%02x%02x%02x)\n\r", buf[0], buf[1], buf[2]);
cmd.cmd = CMD_BOOT_APPLICATION;
cmd.mode = BLMC_CMD_WRITE | BLMC_CMD_0_ARG;
cmd.size = 0;
twi_cmd(i, &cmd);
}
}
void at91_twi_init(void)
{
/* enable Clock */
*AT91C_PMC_PCER = (1 << AT91C_ID_TWI);
/* SDA & SCL from Peripheral A, Open Drain, no Pullup */
AT91S_PIO *pio = AT91C_BASE_PIOA;
pio->PIO_ASR = AT91C_PA3_TWD | AT91C_PA4_TWCK;
pio->PIO_PDR = AT91C_PA3_TWD | AT91C_PA4_TWCK;
pio->PIO_MDER = AT91C_PA3_TWD | AT91C_PA4_TWCK;
pio->PIO_PPUDR = AT91C_PA3_TWD | AT91C_PA4_TWCK;
/* set TWI Clock */
*AT91C_TWI_CWGR = TWI_CLK(200000) | (5<<16);
/* disable all (known) interrupts */
*AT91C_TWI_IDR = AT91C_TWI_TXCOMP | AT91C_TWI_RXRDY | AT91C_TWI_TXRDY | AT91C_TWI_NACK;
/* level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_TWI] = IRQPRIO_TWI | AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_TWI] = (uint32_t)twi_isr;
aic->AIC_IECR = (1 << AT91C_ID_TWI);
/* enable teh monster */
*AT91C_TWI_CR = AT91C_TWI_MSEN;
}

520
src/at91_udp.c Normal file
View File

@ -0,0 +1,520 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdio.h>
#include "AT91SAM7S256.h"
#include "at91_pio.h"
#include "board.h"
#include "usb_ch9.h"
#include "usb_cdc.h"
#include "usb_dfu.h"
#define csr_clear_flags(csr, flags) \
while ((csr) & (flags)) \
(csr) &= ~(flags);
#define csr_set_flags(csr, flags) \
while (((csr) & (flags)) != (flags)) \
(csr) |= (flags);
// TODO: name?
struct udp_transfer {
uint16_t address;
uint16_t maxpkt;
// TODO: last bank used / ping pong
// TODO: direction (IN/OUT)
uint16_t length;
uint16_t curpos;
char *data;
void (*complete_cb)(void);
// TODO: privdata?
};
static uint16_t current_address;
static uint16_t current_config;
static uint16_t current_interface;
static struct udp_transfer ep_transfer[4];
static const struct usb_device_descriptor dev_descriptor = {
.bLength = sizeof(struct usb_device_descriptor),
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0110,
.bMaxPacketSize0 = 8,
.idVendor = USB_VENDOR_ID,
.idProduct = USB_PRODUCT_ID +1,
.bcdDevice = 0x0001,
.bNumConfigurations = 1,
};
struct my_config {
struct usb_config_descriptor cfg;
struct usb_interface_descriptor ctrl_iface;
struct usb_cdc_header_desc cdc_header;
struct usb_cdc_call_mgmt_descriptor cdc_call_mgmt;
struct usb_cdc_acm_descriptor cdc_acm;
struct usb_cdc_union_desc cdc_union;
struct usb_endpoint_descriptor notify_ep;
struct usb_interface_descriptor data_iface;
struct usb_endpoint_descriptor dataout_ep;
struct usb_endpoint_descriptor datain_ep;
struct usb_interface_descriptor dfu_iface;
struct usb_dfu_descriptor dfu;
} __attribute__ ((packed));
static const struct my_config cfg_descriptor = {
.cfg = {
.bLength = sizeof(struct usb_config_descriptor),
.bDescriptorType = USB_DT_CONFIG,
.wTotalLength = sizeof(struct my_config),
.bNumInterfaces = 3,
.bConfigurationValue = 1,
.bmAttributes = USB_CONFIG_ATT_SELFPOWER | USB_CONFIG_ATT_WAKEUP,
.bMaxPower = 50,
},
.ctrl_iface = {
.bLength = sizeof(struct usb_interface_descriptor),
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_COMM,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = 1,
},
.cdc_header = {
.bLength = sizeof(struct usb_cdc_header_desc),
.bDescriptorType = USB_DT_CS_INTERFACE,
.bDescriptorSubType = USB_CDC_HEADER_TYPE,
.bcdCDC = 0x0110,
},
.cdc_call_mgmt = {
.bLength = sizeof(struct usb_cdc_call_mgmt_descriptor),
.bDescriptorType = USB_DT_CS_INTERFACE,
.bDescriptorSubType = USB_CDC_CALL_MANAGEMENT_TYPE,
.bmCapabilities = USB_CDC_CALL_MGMT_CAP_CALL_MGMT,
.bDataInterface = 1,
},
.cdc_acm = {
.bLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = USB_DT_CS_INTERFACE,
.bDescriptorSubType = USB_CDC_ACM_TYPE,
.bmCapabilities = (USB_CDC_CAP_BRK | USB_CDC_CAP_LINE | USB_CDC_COMM_FEATURE),
},
.cdc_union = {
.bLength = sizeof(struct usb_cdc_union_desc),
.bDescriptorType = USB_DT_CS_INTERFACE,
.bDescriptorSubType = USB_CDC_UNION_TYPE,
.bMasterInterface0 = 0,
.bSlaveInterface0 = 1,
},
.notify_ep = {
.bLength = sizeof(struct usb_endpoint_descriptor),
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = USB_DIR_IN | 0x03,
.bmAttributes = USB_ENDPOINT_XFER_INT,
.wMaxPacketSize = 64,
.bInterval = 10,
},
.data_iface = {
.bLength = sizeof(struct usb_interface_descriptor),
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_CDC_DATA,
},
.dataout_ep = {
.bLength = sizeof(struct usb_endpoint_descriptor),
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = USB_DIR_OUT | 0x01,
.bmAttributes = USB_ENDPOINT_XFER_BULK,
.wMaxPacketSize = 64,
},
.datain_ep = {
.bLength = sizeof(struct usb_endpoint_descriptor),
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = USB_DIR_IN | 0x02,
.bmAttributes = USB_ENDPOINT_XFER_BULK,
.wMaxPacketSize = 64,
},
.dfu_iface = {
.bLength = sizeof(struct usb_interface_descriptor),
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 2,
.bNumEndpoints = 0,
.bInterfaceClass = USB_CLASS_APP_SPEC,
.bInterfaceSubClass = 0x01, /* DFU */
},
.dfu = {
.bLength = sizeof(struct usb_dfu_descriptor),
.bDescriptorType = USB_TYPE_DFU,
.bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_CAN_UPLOAD,
.wDetachTimeOut = 0xff00,
.wTransferSize = AT91C_IFLASH_PAGE_SIZE,
.bcdDFUVersion = 0x0100,
},
};
static struct dfu_status dfu_status = {
.bStatus = DFU_STATUS_OK,
.bwPollTimeout = {0x00, 0x04, 0x00},
.bState = DFU_STATE_appIDLE,
};
static void udp_configure_ep(const struct usb_endpoint_descriptor *desc)
{
/* get endpoint type (ctrl, iso, bulb, int) */
uint32_t eptype = desc->bmAttributes & USB_ENDPOINT_XFERTYPE_MASK;
if (desc->bEndpointAddress & USB_ENDPOINT_DIR_MASK)
eptype |= 0x04;
/* get endpoint address, set Max Packet Size */
uint32_t address = desc->bEndpointAddress & USB_ENDPOINT_NUMBER_MASK;
ep_transfer[address].maxpkt = desc->wMaxPacketSize;
/* configure UDP endpoint and enable interrupt */
AT91C_UDP_CSR[address] = AT91C_UDP_EPEDS | (eptype << 8);
*AT91C_UDP_IER = (1 << address);
}
static void udp_fill_fifo(struct udp_transfer *trans)
{
uint16_t ep = trans->address;
if (AT91C_UDP_CSR[ep] & AT91C_UDP_TXPKTRDY) {
printf("TX!RDY\n\r");
return;
}
/* fill fifo */
uint16_t max = trans->maxpkt;
while (trans->curpos < trans->length && max--)
AT91C_UDP_FDR[ep] = trans->data[trans->curpos++];
/* trigger transmission */
AT91C_UDP_CSR[ep] |= AT91C_UDP_TXPKTRDY;
}
static void udp_send_data(struct udp_transfer *trans, const char *data,
uint32_t length, void (*complete_cb)(void))
{
if (trans->length != trans->curpos) {
printf("TXOVF\n\r");
return;
}
/* setup data transmission */
trans->length = length;
trans->curpos = 0;
trans->data = (char *)data;
trans->complete_cb = complete_cb;
udp_fill_fifo(trans);
}
/* stalls the endpoint */
static void udp_send_stall(uint32_t ep)
{
printf("stall\n\r");
AT91C_UDP_CSR[ep] |= AT91C_UDP_FORCESTALL;
}
/*
* set local address
* (USB_REQ_SET_ADDRESS callback)
*/
static void udp_txcb_setaddress(void)
{
*AT91C_UDP_FADDR = (AT91C_UDP_FEN | current_address);
*AT91C_UDP_GLBSTATE = AT91C_UDP_FADDEN;
}
/*
* configure endpoints
* (USB_REQ_SET_CONFIGURATION callback)
*/
static void udp_txcb_setconfig(void)
{
udp_configure_ep(&cfg_descriptor.notify_ep);
udp_configure_ep(&cfg_descriptor.datain_ep);
udp_configure_ep(&cfg_descriptor.dataout_ep);
/* set UDP to "configured" */
*AT91C_UDP_GLBSTATE = AT91C_UDP_CONFG;
}
static void udp_txcb_setinterface(void)
{
printf("claim interface %d\n\r", current_interface);
}
static void udp_handle_ctrlrequest(struct usb_ctrlrequest *req)
{
printf("typ:0x%02x req:0x%02x val:0x%04x idx:0x%04x len:0x%04x\n\r",
req->bRequestType, req->bRequest, req->wValue, req->wIndex, req->wLength);
switch (req->bRequestType & (USB_TYPE_MASK | USB_RECIP_MASK)) {
case (USB_TYPE_STANDARD | USB_RECIP_DEVICE): /* 0x00/0x80 */
switch (req->bRequest) {
case USB_REQ_SET_ADDRESS: /* 0x05 */
current_address = req->wValue;
udp_send_data(&ep_transfer[0], NULL, 0, udp_txcb_setaddress);
break;
case USB_REQ_GET_DESCRIPTOR: /* 0x06 */
switch (req->wValue >> 8) {
case USB_DT_DEVICE: /* 0x01 */
udp_send_data(&ep_transfer[0], (const char *)&dev_descriptor,
MIN(sizeof(dev_descriptor), req->wLength), NULL);
break;
case USB_DT_CONFIG: /* 0x02 */
udp_send_data(&ep_transfer[0], (const char *)&cfg_descriptor,
MIN(sizeof(cfg_descriptor), req->wLength), NULL);
break;
default:
udp_send_stall(0);
break;
}
break;
case USB_REQ_SET_CONFIGURATION: /* 0x09 */
current_config = req->wValue;
udp_send_data(&ep_transfer[0], NULL, 0, udp_txcb_setconfig);
break;
default:
udp_send_stall(0);
break;
}
break;
case (USB_TYPE_STANDARD | USB_RECIP_INTERFACE): /* 0x01/0x81 */
// TODO: follow current_interface
switch (req->bRequest) {
case USB_REQ_SET_INTERFACE: /* 0x0b */
current_interface = req->wIndex;
udp_send_data(&ep_transfer[0], NULL, 0, udp_txcb_setinterface);
break;
default:
udp_send_stall(0);
break;
}
break;
case (USB_TYPE_CLASS | USB_RECIP_INTERFACE): /* 0x21/0xA1 */
// TODO: follow current_interface
switch (req->bRequest) {
case USB_REQ_DFU_DETACH: /* 0x00 */
udp_send_data(&ep_transfer[0], NULL, 0, NULL);
break;
case USB_REQ_DFU_GETSTATUS: /* 0x03 */
udp_send_data(&ep_transfer[0], (const char *)&dfu_status,
MIN(sizeof(struct dfu_status), req->wLength), NULL);
break;
case USB_CDC_REQ_SET_LINE_CODING: /* 0x20 */
// TODO: read 7 data bytes
udp_send_data(&ep_transfer[0], NULL, 0, NULL);
break;
case USB_CDC_REQ_SET_CONTROL_LINE_STATE: /* 0x22 */
udp_send_data(&ep_transfer[0], NULL, 0, NULL);
break;
default:
udp_send_stall(0);
break;
}
break;
default:
udp_send_stall(0);
break;
}
}
static void udp_handle_ep(uint32_t ep)
{
AT91_REG *csr = &AT91C_UDP_CSR[ep];
/* endpoint enabled? */
if (!(*csr & AT91C_UDP_EPEDS))
return;
/* ctrl request packet? */
if (*csr & AT91C_UDP_RXSETUP) {
struct usb_ctrlrequest req;
uint8_t *p;
for (p = (uint8_t *)&req; p < (uint8_t *)(&req +1); p++)
*p = AT91C_UDP_FDR[ep];
/* set data phase transfer direction */
if (req.bRequestType & USB_DIR_IN)
*csr |= AT91C_UDP_DIR;
/* clear interrupt (THIS MUST USE csr_clear_flags()!) */
csr_clear_flags(*csr, AT91C_UDP_RXSETUP);
udp_handle_ctrlrequest(&req);
}
/* transmit complete? */
if (*csr & AT91C_UDP_TXCOMP) {
struct udp_transfer *trans = &ep_transfer[ep];
/* refill fifo, if transfer is incomplete */
if (trans->length != trans->curpos)
udp_fill_fifo(trans);
/* execute callback when transfer is complete */
else if (trans->complete_cb)
trans->complete_cb();
/* clear interrupt */
*csr &= ~(AT91C_UDP_TXCOMP);
}
/* clear STALLSENT interrupt */
if (*csr & AT91C_UDP_STALLSENT)
csr_clear_flags(*csr, (AT91C_UDP_STALLSENT | AT91C_UDP_FORCESTALL));
/* data ready to read? */
if (*csr & (AT91C_UDP_RX_DATA_BK0 | AT91C_UDP_RX_DATA_BK1)) {
uint16_t len = (*csr & AT91C_UDP_RXBYTECNT) >> 16;
if (len) {
printf("rx: ");
while (len--)
printf("0x%02x ", AT91C_UDP_FDR[ep]);
printf("\n\r");
} else {
/* clear a pending transfer! */
ep_transfer[ep].length = 0;
ep_transfer[ep].curpos = 0;
}
/* TODO: ping pong FIFOs */
if (*csr & AT91C_UDP_RX_DATA_BK0)
csr_clear_flags(*csr, AT91C_UDP_RX_DATA_BK0);
if (*csr & AT91C_UDP_RX_DATA_BK1)
csr_clear_flags(*csr, AT91C_UDP_RX_DATA_BK1);
}
}
static void udp_isr(void)
{
uint32_t isr = *AT91C_UDP_ISR;
if (isr & AT91C_UDP_ENDBUSRES) {
printf("usb reset\n\r");
AT91S_UDP *udp = AT91C_BASE_UDP;
/* reset all endpoints */
udp->UDP_RSTEP = (AT91C_UDP_EP0 | AT91C_UDP_EP1 |
AT91C_UDP_EP2 | AT91C_UDP_EP3) ;
udp->UDP_RSTEP = 0;
/* clear all transfers, set default values */
uint32_t i;
for (i = 0; i < 4; i++) {
ep_transfer[i].address = i;
ep_transfer[i].maxpkt = 64;
ep_transfer[i].length = 0;
ep_transfer[i].curpos = 0;
}
ep_transfer[0].maxpkt = 8;
/* Configure endpoint0 as Control EP */
udp->UDP_CSR[0] = (AT91C_UDP_EPEDS | AT91C_UDP_EPTYPE_CTRL);
/* enable ep0 Interrupt, disable all others */
udp->UDP_IER = AT91C_UDP_EPINT0;
udp->UDP_IDR = AT91C_UDP_EPINT1 | AT91C_UDP_EPINT2 | AT91C_UDP_EPINT3 |
AT91C_UDP_RXSUSP | AT91C_UDP_RXRSM | AT91C_UDP_SOFINT |
AT91C_UDP_WAKEUP;
}
/* Handle Endpoint Interrupts */
uint32_t i;
for (i = 0; i < 4; i++) {
if (isr & (1<<i))
udp_handle_ep(i);
}
/* clear all unhandled interrupts */
*AT91C_UDP_ICR = isr & (AT91C_UDP_RXSUSP | AT91C_UDP_RXRSM |
AT91C_UDP_ENDBUSRES | AT91C_UDP_WAKEUP);
}
void at91_udp_init(void)
{
/* configure & disable Pullup, disable Pullup von VBUS */
AT91PS_PIO pio = AT91C_BASE_PIOA;
pio->PIO_CODR = UDP_PULLUP;
pio->PIO_PER = UDP_PULLUP;
pio->PIO_OER = UDP_PULLUP;
// TODO: needed?
pio->PIO_PPUDR = UDP_VBUS_MON;
/* UDPCK (48MHz) = PLLCK / 2 */
*AT91C_CKGR_PLLR |= AT91C_CKGR_USBDIV_1;
/* enable UDP clocks */
*AT91C_PMC_SCER = AT91C_PMC_UDP;
*AT91C_PMC_PCER = (1 << AT91C_ID_UDP);
/* enable transmitter */
*AT91C_UDP_TXVC &= ~AT91C_UDP_TXVDIS;
/* clear & disable all UDP interrupts */
*AT91C_UDP_IDR = AT91C_UDP_EPINT0 | AT91C_UDP_EPINT1 | AT91C_UDP_EPINT2 |
AT91C_UDP_EPINT3 | AT91C_UDP_RXSUSP | AT91C_UDP_RXRSM |
AT91C_UDP_SOFINT | AT91C_UDP_WAKEUP;
*AT91C_UDP_ICR = AT91C_UDP_RXSUSP | AT91C_UDP_RXRSM | AT91C_UDP_SOFINT |
AT91C_UDP_ENDBUSRES | AT91C_UDP_WAKEUP ;
/* level triggered, own vector */
AT91S_AIC *aic = AT91C_BASE_AIC;
aic->AIC_SMR[AT91C_ID_UDP] = IRQPRIO_UDP | AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL;
aic->AIC_SVR[AT91C_ID_UDP] = (uint32_t)udp_isr;
aic->AIC_IECR = (1 << AT91C_ID_UDP);
pio_trigger_isr(UDP_VBUS_MON);
}
static void udp_vbus_monitor(uint32_t status, uint32_t input)
{
if (input & UDP_VBUS_MON)
/* usb connected -> enable pullup */
*AT91C_PIOA_SODR = UDP_PULLUP;
else
/* usb got diconnected -> disable pullup */
*AT91C_PIOA_CODR = UDP_PULLUP;
}
PIO_PINCHANGE_ISR(UDP_VBUS_MON, udp_vbus_monitor);

192
src/fifo.c Normal file
View File

@ -0,0 +1,192 @@
/***************************************************************************
* Copyright (C) 01/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "AT91SAM7S256.h"
#include "atomic.h"
#include "fifo.h"
#include "static_alloc.h"
#define FIFO_MASK(x) ((x)->size -1)
/*
* get used bytes (under lock)
* all other operations don't need locks:
* - only fifo_put/fifo_rxpdc are allowed to increment fifo->in
* - only fifo_get/fifo_txpdc are allowed to increment fifo->out
* a integer overflow (4gb) of fifo->in / fifo->out could cause trouble
*/
static uint32_t fifo_used(struct fifo *fifo)
{
disable_irqs();
uint32_t used = fifo->in - fifo->out;
restore_irqs();
return used;
}
/*
* append data to fifo
* returns number of bytes copied
*/
uint32_t fifo_put(struct fifo *fifo, const char *buf, uint32_t len)
{
uint32_t left = fifo->size - fifo_used(fifo);
if (len > left)
len = left;
uint32_t count = len;
while (count--)
fifo->buf[fifo->in++ & FIFO_MASK(fifo)] = *buf++;
return len;
}
/*
* get data from fifo
* returns number of bytes copied
*/
uint32_t fifo_get(struct fifo *fifo, char *buf, uint32_t len)
{
uint32_t used = fifo_used(fifo);
if (len > used)
len = used;
uint32_t count = len;
while (count--)
*buf++ = fifo->buf[fifo->out++ & FIFO_MASK(fifo)];
return len;
}
/*
* receive data via PDC and put it into fifo
*/
uint32_t fifo_rxpdc(struct fifo *fifo, AT91S_PDC *pdc, uint16_t maxsize)
{
/* account previous PDC transfer */
fifo->in += fifo->pdc_rx;
uint32_t free = fifo->size - fifo_used(fifo);
if (free) {
/* calc pointer for next transfer */
uint32_t first_idx = (fifo->in & FIFO_MASK(fifo));
pdc->PDC_RPR = (uint32_t)(fifo->buf + first_idx);
/* check for buffer end -> split transfer */
if (first_idx + free <= (fifo->size -1)) {
fifo->pdc_rx = free;
} else {
fifo->pdc_rx = fifo->size - first_idx;
}
/* split in maxsize chunks */
if (maxsize && fifo->pdc_rx > maxsize)
fifo->pdc_rx = maxsize;
/* start transfer */
pdc->PDC_RCR = fifo->pdc_rx;
} else {
/* no data in buffer */
fifo->pdc_rx = 0;
}
return fifo->pdc_rx;
}
/*
* transmit fifo via PDC
* returns 0 if no transfer was started
*/
uint32_t fifo_txpdc(struct fifo *fifo, AT91S_PDC *pdc, uint16_t maxsize)
{
/* account previous PDC transfer */
fifo->out += fifo->pdc_tx;
uint32_t used = fifo_used(fifo);
if (used) {
/* calc pointer for next transfer */
uint32_t first_idx = (fifo->out & FIFO_MASK(fifo));
pdc->PDC_TPR = (uint32_t)(fifo->buf + first_idx);
/* check for buffer end -> split transfer */
if (first_idx + used <= (fifo->size -1)) {
fifo->pdc_tx = used;
} else {
fifo->pdc_tx = fifo->size - first_idx;
}
/* split in maxsize chunks */
if (maxsize && fifo->pdc_tx > maxsize)
fifo->pdc_tx = maxsize;
/* start transfer */
pdc->PDC_TCR = fifo->pdc_tx;
} else {
/* no data in buffer */
fifo->pdc_tx = 0;
}
return fifo->pdc_tx;
}
/*
* put one byte into the fifo
* returns 0 if fifo was full
*/
uint32_t fifo_putbyte(struct fifo *fifo, char c)
{
uint32_t left = fifo->size - fifo_used(fifo);
if (left) {
fifo->buf[fifo->in++ & FIFO_MASK(fifo)] = c;
return 1;
}
return 0;
}
/*
* gets one byte from fifo
* returns 0 if fifo was empty
*/
uint32_t fifo_getbyte(struct fifo *fifo, char *p)
{
uint32_t used = fifo_used(fifo);
if (used) {
*p = fifo->buf[fifo->out++ & FIFO_MASK(fifo)];
return 1;
}
return 0;
}
/*
* allocs a fifo from static_alloc space
*/
struct fifo * fifo_alloc(uint32_t size)
{
size = next_powerof2(size);
struct fifo *fifo = static_alloc(sizeof(struct fifo) + size);
fifo->size = size;
fifo->in = 0;
fifo->out = 0;
fifo->pdc_tx = 0;
fifo->pdc_rx = 0;
return fifo;
}

60
src/static_alloc.c Normal file
View File

@ -0,0 +1,60 @@
/***************************************************************************
* Copyright (C) 02/2008 by Olaf Rempel *
* razzor@kopf-tisch.de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <stdint.h>
#include "AT91SAM7S256.h"
#include "board.h"
//#include "static_alloc.h"
#define ALIGN(x) (((x) +3) & ~3)
/* extern symbols, defined in ldscript */
extern void * __bss_end__;
extern void * __stack_top__;
static uint32_t static_alloc_pos;
void * static_alloc(uint32_t size)
{
if (static_alloc_pos == 0)
static_alloc_pos = ALIGN((uint32_t)&__bss_end__);
uint32_t retval = static_alloc_pos;
size = ALIGN(size);
static_alloc_pos += size;
return (void *)retval;
}
uint32_t static_alloc_used(void)
{
return static_alloc_pos - (uint32_t)&__bss_end__;
}
// TODO: find a better place
uint32_t next_powerof2(uint32_t value)
{
uint32_t i;
value--;
for (i = 1; i < 32; i = i * 2)
value |= value >> i;
return value +1;
}

286
src/stdio/_putf.c Normal file
View File

@ -0,0 +1,286 @@
#include <stddef.h> /* size_t */
#include <stdarg.h> /* va_list */
#include <stdio.h>
#include <string.h>
#include "_putf.h"
#define BUF 16
#define PADSIZE 16
static const char blanks[PADSIZE] = {
' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
' ', ' ', ' ', ' ', ' ', ' ', ' ', ' '
};
static const char zeroes[PADSIZE] = {
'0', '0', '0', '0', '0', '0', '0', '0',
'0', '0', '0', '0', '0', '0', '0', '0'
};
static void _putpad(int _putb(void *, const char *, size_t), void *base, const char *padch, int count)
{
while (count > PADSIZE) {
_putb(base, padch, PADSIZE);
count -= PADSIZE;
}
if (count > 0)
_putb(base, padch, count);
}
/*
* Flags used during conversion.
*/
#define ALT 0x01 /* alternate form */
#define LADJUST 0x04 /* left adjustment */
#define LONGINT 0x08 /* long integer */
#define ZEROPAD 0x10 /* zero (as opposed to blank) pad */
int _putf(int _putb(void *, const char *, size_t), void *base, const char *fmt, va_list ap)
{
int rc = 0; /* return value accumulator */
for (;;) {
unsigned char ch; /* character from fmt */
int size; /* size of converted field or string */
char *cp = (char *)fmt;
while ((ch = *fmt) && (ch != '%'))
fmt++;
int n = fmt - cp;
if (n) {
_putb(base, cp, n);
rc += n;
}
if (ch == 0)
break;
fmt++;
char flags = 0; /* flags as above */
char sign = 0; /* sign prefix (' ', '+', '-', or \0) */
int width = 0; /* width from format (%8d), or 0 */
int prec = -1; /* precision from format (%.3d), or -1 */
int dprec = 0; /* a copy of prec if [diouxX], 0 otherwise */
for (;;) {
ch = *fmt++;
if (ch == ' ') {
if (!sign)
sign = ' ';
} else if (ch == '+') {
sign = '+';
} else if (ch == '-') {
flags |= LADJUST;
} else if (ch == '#') {
flags |= ALT;
} else if (ch == '0') {
flags |= ZEROPAD;
} else if (ch == 'l') {
flags |= LONGINT;
} else if (ch == 'z') {
if (sizeof(size_t) > sizeof(int))
flags |= LONGINT;
} else if (ch == '*') {
width = va_arg(ap, int);
if (width < 0) {
flags |= LADJUST;
width = -width;
}
} else if (ch == '.') {
if (*fmt == '*') {
fmt++;
prec = va_arg(ap, int);
} else {
prec = 0;
while (*fmt >= '0' && *fmt <= '9')
prec = 10 * prec + (*fmt++ - '0');
}
if (prec < 0)
prec = -1;
} else if (ch >= '1' && ch <= '9') {
width = ch - '0';
while (*fmt >= '0' && *fmt <= '9')
width = 10 * width + (*fmt++ - '0');
} else {
break;
}
}
unsigned long ulval; /* integer arguments %[diouxX] */
char buf[BUF]; /* space for %c, %[diouxX], %[eEfgG] */
switch (ch) {
case 'c':
*(cp = buf) = va_arg(ap, int);
size = 1;
sign = 0;
break;
case 'P':
case 's':
cp = va_arg(ap, char *);
if (cp == 0)
cp = "(null)";
if (prec >= 0) {
char *p = memchr(cp, 0, (size_t) prec);
if (p) {
size = p - cp;
if (size > prec)
size = prec;
} else {
size = prec;
}
} else {
size = strlen(cp);
sign = 0;
}
break;
case 'u':
sign = 0;
case 'd':
case 'i':
if (flags & LONGINT) {
ulval = va_arg(ap, unsigned long);
} else if (ch == 'u') {
ulval = va_arg(ap, unsigned int);
} else {
ulval = va_arg(ap, int);
}
if (ch != 'u' && (long) ulval < 0) {
ulval = (unsigned long) (-((long) ulval));
sign = '-';
}
if ((dprec = prec) >= 0)
flags &= ~ZEROPAD;
cp = buf + BUF;
if (ulval || prec) {
if (ulval < 10) {
*--cp = (char) ulval + '0';
} else {
do {
*--cp = (char) (ulval % 10) + '0';
ulval /= 10;
} while (ulval);
}
}
size = buf + BUF - cp;
break;
case 'o':
ulval = (flags & LONGINT) ? va_arg(ap, unsigned long) : va_arg(ap, unsigned int);
sign = 0;
if ((dprec = prec) >= 0)
flags &= ~ZEROPAD;
cp = buf + BUF;
if (ulval || prec) {
do {
*--cp = (char) (ulval & 7) + '0';
ulval >>= 3;
} while (ulval);
if ((flags & ALT) != 0 && *cp != '0')
*--cp = '0';
}
size = buf + BUF - cp;
break;
case 'p':
case 'X':
case 'x':
if (ch == 'p') {
ulval = (unsigned long) va_arg(ap, void *);
flags |= ALT;
ch = 'x';
} else {
ulval = (flags & LONGINT) ? va_arg(ap, unsigned long) : va_arg(ap, unsigned int);
}
sign = 0;
if ((dprec = prec) >= 0)
flags &= ~ZEROPAD;
char *xdigs = (ch == 'X') ? "0123456789ABCDEF" : "0123456789abcdef";
cp = buf + BUF;
do {
*--cp = xdigs[ulval & 0x0f];
ulval >>= 4;
} while (ulval);
if (flags & ALT) {
*--cp = ch;
*--cp = '0';
}
size = buf + BUF - cp;
break;
case 'g':
case 'G':
case 'e':
case 'E':
case 'f':
(void) va_arg(ap, long);
default:
if (ch == 0)
return rc;
cp = buf;
*cp = ch;
size = 1;
sign = '\0';
break;
}
int realsz = dprec > size ? dprec : size;
if (sign)
realsz++;
if ((flags & (LADJUST | ZEROPAD)) == 0)
_putpad(_putb, base, blanks, width - realsz);
if (sign)
_putb(base, &sign, 1);
if ((flags & (LADJUST | ZEROPAD)) == ZEROPAD)
_putpad(_putb, base, zeroes, width - realsz);
_putpad(_putb, base, zeroes, dprec - size);
if (size)
_putb(base, cp, size);
if (flags & LADJUST)
_putpad(_putb, base, blanks, width - realsz);
rc += (width >= realsz) ? width : realsz;
}
return rc;
}

6
src/stdio/_putf.h Normal file
View File

@ -0,0 +1,6 @@
#ifndef _PUTF_H_
#define _PUTF_H_
int _putf(int _putb(void *, const char *, size_t), void *base, const char *fmt, va_list ap);
#endif /* _PUTF_H_ */

61
src/stdio/printf.c Normal file
View File

@ -0,0 +1,61 @@
#include <stddef.h> /* size_t */
#include <stdarg.h> /* va_list */
#include "_putf.h"
#include "at91_dbgu.h"
int printf(const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
int rc = _putf(at91_dbgu_write, NULL, fmt, ap);
va_end(ap);
return rc;
}
int inline puts(const char *p)
{
at91_dbgu_puts(p);
return 0;
}
int inline putchar(int c)
{
at91_dbgu_putc(c);
return 0;
}
struct snprintf_data {
char *bufstart;
size_t buflen;
int pos;
};
int snprintf_helper(void *base, const char *buf, size_t len)
{
struct snprintf_data *data = (struct snprintf_data *)base;
int count = 0;
while (len-- && (data->pos < data->buflen))
data->bufstart[data->pos++] = *buf++;
return count;
}
int snprintf(char *buf, size_t len, const char *fmt, ...)
{
struct snprintf_data data = {
.bufstart = buf,
.buflen = len,
.pos = 0,
};
va_list ap;
va_start(ap, fmt);
int rc = _putf(snprintf_helper, (void *)&data, fmt, ap);
va_end(ap);
buf[data.pos] = '\0';
return rc;
}