CPU specific files for the AT91SAM7S ARM-based microcontrollers

This commit is contained in:
ksb 2007-02-24 00:09:45 +00:00
parent 9a5501485b
commit 13af443115
22 changed files with 3331 additions and 0 deletions

View file

@ -0,0 +1,172 @@
/***********************************************************************/
/* */
/* Linker Script File for the AT91SAM7S64 - Code in ROM */
/* */
/***********************************************************************/
/* modified for arm-elf-gcc by Martin Thomas */
/* extensions: - Section for Functions in RAM, */
/* Exeception-Vector remapping */
/* modifications Copyright Martin Thomas 2005 */
/* */
/* */
/* Based on file that has been a part of the uVision/ARM development */
/* tools, Copyright KEIL ELEKTRONIK GmbH 2002-2004 */
/***********************************************************************/
/*
//*** <<< Use Configuration Wizard in Context Menu >>> ***
*/
/*
// <h> Memory Configuration
// <h> Code (Read Only)
// <o> Start <0x0-0xFFFFFFFF>
// <o1> Size <0x0-0xFFFFFFFF>
// </h>
// <h> Data (Read/Write)
// <o2> Start <0x0-0xFFFFFFFF>
// <o3> Size <0x0-0xFFFFFFFF>
// </h>
// </h>
*/
/* Memory Definitions */
MEMORY
{
CODE (rx) : ORIGIN = 0x00100000, LENGTH = 0x00010000
DATA (rw) : ORIGIN = 0x00200000, LENGTH = 0x00004000
}
/* Section Definitions */
SECTIONS
{
/* first section is .text which is used for code */
.text :
{
/* *startup.o (.text) */ /* Startup code */
KEEP(*(.vectrom)) /* added by mthomas */
KEEP(*(.init))
*(.text .text.*)
*(.gnu.linkonce.t.*)
*(.glue_7t .glue_7)
KEEP(*(.fini))
*(.gcc_except_table)
} >CODE =0
. = ALIGN(4);
/* .ctors .dtors are used for c++ constructors/destructors */
/* added by mthomas, based on an Anglia-Designs example for STR7 */
.ctors :
{
PROVIDE(__ctors_start__ = .);
KEEP(*(SORT(.ctors.*)))
KEEP(*(.ctors))
PROVIDE(__ctors_end__ = .);
} >CODE
.dtors :
{
PROVIDE(__dtors_start__ = .);
KEEP(*(SORT(.dtors.*)))
KEEP(*(.dtors))
PROVIDE(__dtors_end__ = .);
} >CODE
/* .rodata section which is used for read-only data (constants) */
.rodata :
{
*(.rodata .rodata.*)
*(.gnu.linkonce.r.*)
} >CODE
. = ALIGN(4);
_etext = . ;
PROVIDE (etext = .);
.data : AT (_etext)
{
_data = . ;
KEEP(*(.vectram)) /* added by mthomas */
*(.data)
SORT(CONSTRUCTORS)
. = ALIGN(4);
*(.fastrun) /* "RAM-Functions" */ /* added by mthomas */
} >DATA
. = ALIGN(4);
_edata = . ;
PROVIDE (edata = .);
/* .bss section which is used for uninitialized data */
.bss :
{
__bss_start = . ;
__bss_start__ = . ;
*(.bss)
*(COMMON)
} >DATA
. = ALIGN(4);
__bss_end__ = . ;
__bss_end__ = . ;
_end = .;
PROVIDE (end = .);
.stack ORIGIN(DATA) + LENGTH(DATA) - 0x0c0c :
{
__stack_start__ = . ;
*(.stack)
. = ALIGN(4);
__stack_end__ = . ;
} >DATA
__heap_start__ = __bss_end__ ;
__heap_end__ = __stack_start__ ;
/* 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 debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
/* 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) }
}

1917
cpu/at91sam7s/AT91SAM7S64.h Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,139 @@
# Adapted from Makefile.msp430
### Check if we are running under Windows
ifndef WINDIR
ifdef OS
ifneq (,$(findstring Windows,$(OS)))
WINDIR := Windows
endif
endif
endif
ifdef nodeid
CFLAGS += -DNODEID=$(nodeid)
endif
### Define the CPU directory
CONTIKI_CPU=$(CONTIKI)/cpu/at91sam7s
### Define the source files we have in the MSP430 port
AT91SAM7S = clock.c debug-uart.c interrupt_utils.c newlib-syscalls.c sys-interrupt.c
CONTIKI_TARGET_SOURCEFILES += $(AT91SAM7S)
CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES)
CONTIKIDIRS=$(CONTIKI)/core/sys:$(CONTIKI)/core/dev:$(CONTIKI)/core/cfs:$(CONTIKI)/core/loader:$(CONTIKI)/core/net:$(CONTIKI)/core/lib
### Compiler definitions
CC = arm-elf-gcc
LD = arm-elf-gcc
AS = arm-elf-as
AR = arm-elf-ar
NM = arm-elf-nm
OBJCOPY = arm-elf-objcopy
STRIP = arm-elf-strip
LINKERSCRIPT = $(CONTIKI_CPU)/AT91SAM7S64-ROM.ld
STARTUP=startup-SAM7S.o
# JTAG program upload
OPENOCD = openocd
OPENOCD_FLASH_CFG = arm7_wig_flash.cfg
OPENOCD_RESET = arm7_wig_reset.cfg
# USB program upload
SAMIAM=Sam_I_Am
SAMIAM_TTY=/dev/ttyACM0
ARCH_FLAGS= -mcpu=arm7tdmi
THUMB_FLAGS=-mthumb -mthumb-interwork
ARM_FLAGS=-mthumb-interwork
CFLAGSNO = -I. -I$(CONTIKI)/core -I$(CONTIKI_CPU) \
-I$(CONTIKI)/platform/$(TARGET) \
${addprefix -I,$(APPDIRS)} \
-DWITH_UIP -DWITH_ASCII -DMCK=$(MCK) \
-Wall $(ARCH_FLAGS) -g
CFLAGS += $(CFLAGSNO) -O -DRUN_AS_SYSTEM -DROM_RUN
LDFLAGS += $(ARCH_FLAGS) -T $(LINKERSCRIPT)
PROJECT_OBJECTFILES += ${addprefix $(OBJECTDIR)/,$(CONTIKI_TARGET_MAIN:.c=.o)}
### Setup directory search path for source files
CONTIKI_TARGET_DIRS_CONCAT = ${addprefix $(CONTIKI)/platform/$(TARGET)/, \
$(CONTIKI_TARGET_DIRS)}
vpath %.c $(PROJECTDIRS) \
$(CONTIKIDIRS) $(APPDIRS) $(CONTIKI_TARGET_DIRS_CONCAT) \
$(CONTIKI_CPU)
vpath %.S $(CONTIKI_CPU)
%-interrupt.o: %-interrupt.c
$(CC) $(CFLAGS) $(ARM_FLAGS) $< -c
%-arm.o: %-arm.c
$(CC) $(CFLAGS) $(ARM_FLAGS) $< -c
interrupt-utils.o: interrupt-utils.c
$(CC) $(CFLAGS) $(ARM_FLAGS) $< -c
%.o: %.c
$(CC) $(CFLAGS) $(THUMB_FLAGS) $< -c
%.o: %.S
$(CC) $(CFLAGS) $(ARM_FLAGS) $< -c
%.ko: %.o
$(LD) --relocatable -T $(CONTIKI_CPU)/merge-rodata.ld $< -o $@
$(STRIP) -K _init -K _fini --strip-unneeded -g -x $@
%.elf: $^ $(STARTUP)
$(CC) $(LDFLAGS) $(CFLAGS) $(THUMB_FLAGS) -nostartfiles -o $@ $^
# Add a namelist to the kernel
%-syms.elf: $^ $(STARTUP)
: | awk -f $(CONTIKI)/tools/mknmlist > $*-tmp.c && mv $*-tmp.c $*-nm.c
$(CC) $(LDFLAGS) $(CFLAGS) $(THUMB_FLAGS) -nostartfiles -o $@ $^ $*-nm.c
$(NM) $@ | awk -f $(CONTIKI)/tools/mknmlist > $*-tmp.c && mv $*-tmp.c $*-nm.c
-test -r $*.exclude && grep -v -f $*.exclude $*-nm.c >$*-tmp.c && mv $*-tmp.c $*-nm.c
$(CC) $(LDFLAGS) $(CFLAGS) $(THUMB_FLAGS) -nostartfiles -o $*-syms.elf $^ $*-nm.c
%.ihx: %.elf
$(OBJCOPY) -O ihex $< $@
%.bin: %.elf
$(OBJCOPY) -O binary $< $@
upload_ocd_%: %.bin
cp $< /tmp/openocd_write.bin
# Clear lock bits
cd $(CONTIKI_CPU)/openocd;$(OPENOCD) -f $(OPENOCD_FLASH_CFG)
-rm /tmp/openocd_write.bin
upload_%: %.ihx
# Clear lock bits
$(SAMIAM) "open $(SAMIAM_TTY) , writew 0xffffff64 5a000004"
$(SAMIAM) "open $(SAMIAM_TTY) , writew 0xffffff64 5a002004"
$(SAMIAM) "open $(SAMIAM_TTY) , flash $< , go"
ocd_reset:
cd $(CONTIKI_CPU)/openocd;$(OPENOCD) -f $(OPENOCD_RESET)
clean:
-rm *.o
-rm *.elf
-rm *.ihx
-rm *.bin
-rm *-nm.c

58
cpu/at91sam7s/clock.c Normal file
View file

@ -0,0 +1,58 @@
#include <sys/clock.h>
#include <sys/cc.h>
#include <sys/etimer.h>
#include <debug-uart.h>
#include <AT91SAM7S64.h>
#include <sys-interrupt.h>
static volatile clock_time_t current_clock = 0;
#define PIV ((MCK/CLOCK_SECOND/16)-1)
static int pit_handler_func()
{
if (!(*AT91C_PITC_PISR & AT91C_PITC_PITS)) return 0; /* Check PIT
Interrupt */
current_clock++;
if(etimer_pending() && etimer_next_expiration_time() <= current_clock) {
etimer_request_poll();
/* dbg_printf("%d,%d\n", clock_time(),etimer_next_expiration_time ()); */
}
(void)*AT91C_PITC_PIVR;
return 1;
}
static SystemInterruptHandler pit_handler = {NULL, pit_handler_func};
void
clock_init()
{
sys_interrupt_append_handler(&pit_handler);
*AT91C_PITC_PIMR = (AT91C_PITC_PITIEN | /* PIT Interrupt Enable */
AT91C_PITC_PITEN | /* PIT Enable */
PIV);
sys_interrupt_enable();
}
clock_time_t
clock_time(void)
{
return current_clock;
}
/* The inner loop takes 4 cycles. The outer 5+SPIN_COUNT*4. */
#define SPIN_TIME 2 /* us */
#define SPIN_COUNT (((MCK*SPIN_TIME/1000000)-5)/4)
void
clock_delay(unsigned int t)
{
#ifdef __THUMBEL__
asm volatile("1: mov r1,%2\n2:\tsub r1,#1\n\tbne 2b\n\tsub %0,#1\n\tbne 1b\n":"=l"(t):"0"(t),"l"(SPIN_COUNT));
#else
#error Must be compiled in thumb mode
#endif
}

193
cpu/at91sam7s/debug-uart.c Normal file
View file

@ -0,0 +1,193 @@
#include <debug-uart.h>
#include <sys-interrupt.h>
/* #include <strformat.h> */
#include <AT91SAM7S64.h>
#include <string.h>
#include <interrupt-utils.h>
#ifndef DBG_XMIT_BUFFER_LEN
#define DBG_XMIT_BUFFER_LEN 256
#endif
#ifndef DBG_RECV_BUFFER_LEN
#define DBG_RECV_BUFFER_LEN 256
#endif
static unsigned char dbg_xmit_buffer[DBG_XMIT_BUFFER_LEN];
static unsigned char dbg_recv_buffer[DBG_RECV_BUFFER_LEN];
static unsigned int dbg_recv_buffer_len = 0;
void
dbg_setup_uart()
{
/* Setup PIO ports */
*AT91C_PIOA_OER = AT91C_PA10_DTXD;
*AT91C_PIOA_ODR = AT91C_PA9_DRXD;
*AT91C_PIOA_ASR = AT91C_PA10_DTXD | AT91C_PA9_DRXD;
*AT91C_PIOA_PDR = AT91C_PA10_DTXD | AT91C_PA9_DRXD;
*AT91C_DBGU_MR = AT91C_US_PAR_NONE | AT91C_US_CHMODE_NORMAL;
*AT91C_DBGU_IDR= 0xffffffff;
*AT91C_DBGU_BRGR = MCK / (115200 * 16);
*AT91C_DBGU_CR = AT91C_US_RXEN | AT91C_US_TXEN;
*AT91C_DBGU_TPR = (unsigned int)dbg_xmit_buffer;
*AT91C_DBGU_TNPR = (unsigned int)dbg_xmit_buffer;
}
static void (*input_func)(const char *inp, unsigned int len) = NULL;
static int dbg_recv_handler_func()
{
if (!(*AT91C_DBGU_CSR & AT91C_US_RXRDY)) return 0;
unsigned char c = *AT91C_DBGU_RHR;
/* Leave one byte for '\0' */
if (dbg_recv_buffer_len < (DBG_RECV_BUFFER_LEN -1)) {
dbg_recv_buffer[dbg_recv_buffer_len++] = c;
}
if (c == '\n') {
dbg_recv_buffer[dbg_recv_buffer_len] = '\0';
if (input_func) input_func((char*)dbg_recv_buffer, dbg_recv_buffer_len);
dbg_recv_buffer_len = 0;
}
return 1;
}
static SystemInterruptHandler dbg_recv_handler = {NULL, dbg_recv_handler_func};
void
dbg_set_input_handler(void (*handler)(const char *inp, unsigned int len))
{
input_func = handler;
sys_interrupt_append_handler(&dbg_recv_handler);
sys_interrupt_enable();
*AT91C_DBGU_IER = AT91C_US_RXRDY;
}
static volatile unsigned char mutex = 0;
unsigned int
dbg_send_bytes(const unsigned char *seq, unsigned int len)
{
unsigned short next_count;
unsigned short current_count;
unsigned short left;
unsigned int save = disableIRQ();
if (mutex) return 0; /* Buffer being updated */
mutex = 1; /* Prevent interrupts from messing up the transmission */
*AT91C_DBGU_PTCR =AT91C_PDC_TXTDIS; /* Stop transmitting */
while(*AT91C_DBGU_PTSR & AT91C_PDC_TXTEN); /* Wait until stopped */
next_count = *AT91C_DBGU_TNCR;
current_count = *AT91C_DBGU_TCR;
left = DBG_XMIT_BUFFER_LEN - next_count - current_count;
if (left > 0) {
if (left < len) len = left;
if (next_count > 0) {
/* Buffer is wrapped */
memcpy(&dbg_xmit_buffer[next_count], seq, len);
*AT91C_DBGU_TNCR = next_count + len;
} else {
unsigned char *to = ((unsigned char*)*AT91C_DBGU_TPR) + current_count;
left = &dbg_xmit_buffer[DBG_XMIT_BUFFER_LEN] - to;
if (len > left) {
unsigned int wrapped = len - left;
memcpy(to, seq, left);
memcpy(dbg_xmit_buffer, &seq[left], wrapped);
*AT91C_DBGU_TCR = current_count + left;
*AT91C_DBGU_TNCR = wrapped;
} else {
memcpy(to, seq, len);
*AT91C_DBGU_TCR = current_count + len;
}
}
} else {
len = 0;
}
*AT91C_DBGU_PTCR =AT91C_PDC_TXTEN; /* Restart transmission */
mutex = 0;
restoreIRQ(save);
return len;
}
static unsigned char dbg_write_overrun = 0;
void
dbg_putchar(const char ch)
{
if (dbg_write_overrun) {
if (dbg_send_bytes((const unsigned char*)"^",1) != 1) return;
}
dbg_write_overrun = 0;
if (dbg_send_bytes((const unsigned char*)&ch,1) != 1) {
dbg_write_overrun = 1;
}
}
void
dbg_blocking_putchar(const char ch)
{
if (dbg_write_overrun) {
while (dbg_send_bytes((const unsigned char*)"^",1) != 1);
}
dbg_write_overrun = 0;
while (dbg_send_bytes((const unsigned char*)&ch,1) != 1);
}
#if 0
static StrFormatResult
dbg_write_cb(void *user_data, const char *data, unsigned int len)
{
if (dbg_send_bytes((const unsigned char*)data, len) != len) {
dbg_write_overrun = 1;
return STRFORMAT_FAILED;
}
return STRFORMAT_OK;
}
void
dbg_printf(const char *format, ...)
{
static const StrFormatContext ctxt = {dbg_write_cb, NULL};
va_list ap;
if (dbg_write_overrun) {
if (dbg_send_bytes((const unsigned char*)"^",1) != 1) return;
}
dbg_write_overrun = 0;
va_start(ap, format);
format_str_v(&ctxt, format, ap);
va_end(ap);
}
static StrFormatResult
dbg_write_blocking_cb(void *user_data, const char *data, unsigned int len)
{
unsigned int left = len;
while(left > 0) {
unsigned int sent = dbg_send_bytes((const unsigned char*)data, left);
left -= sent;
data += sent;
}
return STRFORMAT_OK;
}
void
dbg_blocking_printf(const char *format, ...)
{
static const StrFormatContext ctxt = {dbg_write_blocking_cb, NULL};
va_list ap;
if (dbg_write_overrun) {
while (dbg_send_bytes((const unsigned char*)"^",1) != 1);
}
dbg_write_overrun = 0;
va_start(ap, format);
format_str_v(&ctxt, format, ap);
va_end(ap);
}
#endif
void
dbg_drain()
{
while(!(*AT91C_DBGU_CSR & AT91C_US_TXBUFE));
}

View file

@ -0,0 +1,33 @@
#ifndef __DEBUG_UART_H__1V2039076V__
#define __DEBUG_UART_H__1V2039076V__
void
dbg_setup_uart();
void
dbg_set_input_handler(void (*handler)(const char *inp, unsigned int len));
unsigned int
dbg_send_bytes(const unsigned char *seq, unsigned int len);
#if 0
void
dbg_printf(const char *format, ...)
__attribute__ ((__format__ (__printf__, 1,2)));
void
dbg_blocking_printf(const char *format, ...)
__attribute__ ((__format__ (__printf__, 1,2)));
#endif
void
dbg_putchar(const char ch);
void
dbg_blocking_putchar(const char ch);
void
dbg_drain();
#endif /* __DEBUG_UART_H__1V2039076V__ */

View file

@ -0,0 +1,78 @@
#include <malloc.h>
#include <loader/elfloader-arch-otf.h>
#if 0
#include <stdio.h>
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...) do {} while (0)
#endif
#define ELF32_R_TYPE(info) ((unsigned char)(info))
/* Supported relocations */
#define R_ARM_ABS32 2
#define R_ARM_THM_CALL 10
/* Adapted from elfloader-avr.c */
void
elfloader_arch_relocate(int input_fd,
struct elfloader_output *output,
unsigned int sectionoffset,
char *sectionaddr,
struct elf32_rela *rela, char *addr)
{
unsigned int type;
unsigned char instr[4];
type = ELF32_R_TYPE(rela->r_info);
cfs_seek(input_fd, sectionoffset + rela->r_offset);
/* PRINTF("elfloader_arch_relocate: type %d\n", type); */
/* PRINTF("Addr: %p, Addend: %ld\n", addr, rela->r_addend); */
switch(type) {
case R_ARM_ABS32:
{
int32_t addend;
cfs_read(input_fd, (char*)&addend, 4);
addr += addend;
elfloader_output_write_segment(output,(char*) &addr, 4);
PRINTF("%p: addr: %p\n", sectionaddr +rela->r_offset,
addr);
}
break;
case R_ARM_THM_CALL:
{
int32_t offset;
char *base;
cfs_read(input_fd, (char*)instr, 4);
/* Ignore the addend since it will be zero for calls to symbols,
and I can't think of a case when doing a relative call to
a non-symbol position */
base = sectionaddr + (rela->r_offset + 4);
if (((*(uint16_t*)(instr+2)) & 0x1800) == 0x0800) {
addr = (char*)((((uint32_t)addr) & 0xfffffffd)
| (((uint32_t)base) & 0x00000002));
}
offset = addr - (sectionaddr + (rela->r_offset + 4));
if (offset < -(1<<22) || offset >= (1<<22)) {
PRINTF("elfloader-arm.c: offset %d too large for relative call\n",
(int)offset);
}
/* PRINTF("%p: %04x %04x offset: %d addr: %p\n", sectionaddr +rela->r_offset, *(uint16_t*)instr, *(uint16_t*)(instr+2), (int)offset, addr); */
*(uint16_t*)instr = (*(uint16_t*)instr & 0xf800) | ((offset>>12)&0x07ff);
*(uint16_t*)(instr+2) = ((*(uint16_t*)(instr+2) & 0xf800)
| ((offset>>1)&0x07ff));
elfloader_output_write_segment(output, (char*)instr, 4);
/* PRINTF("cfs_write: %04x %04x\n",*(uint16_t*)instr, *(uint16_t*)(instr+2)); */
}
break;
default:
PRINTF("elfloader-arm.c: unsupported relocation type %d\n", type);
break;
}
}

View file

@ -0,0 +1,84 @@
/******************************************************************************
*
* $RCSfile: interrupt-utils.c,v $
* $Revision: 1.1 $
*
* This module provides the interface routines for setting up and
* controlling the various interrupt modes present on the ARM processor.
* Copyright 2004, R O SoftWare
* No guarantees, warrantees, or promises, implied or otherwise.
* May be used for hobby or commercial purposes provided copyright
* notice remains intact.
*
*****************************************************************************/
#include "interrupt-utils.h"
#define IRQ_MASK 0x00000080
#define FIQ_MASK 0x00000040
#define INT_MASK (IRQ_MASK | FIQ_MASK)
static inline unsigned __get_cpsr(void)
{
unsigned long retval;
asm volatile (" mrs %0, cpsr" : "=r" (retval) : /* no inputs */ );
return retval;
}
static inline void __set_cpsr(unsigned val)
{
asm volatile (" msr cpsr, %0" : /* no outputs */ : "r" (val) );
}
unsigned disableIRQ(void)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr(_cpsr | IRQ_MASK);
return _cpsr;
}
unsigned restoreIRQ(unsigned oldCPSR)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr((_cpsr & ~IRQ_MASK) | (oldCPSR & IRQ_MASK));
return _cpsr;
}
unsigned enableIRQ(void)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr(_cpsr & ~IRQ_MASK);
return _cpsr;
}
unsigned disableFIQ(void)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr(_cpsr | FIQ_MASK);
return _cpsr;
}
unsigned restoreFIQ(unsigned oldCPSR)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr((_cpsr & ~FIQ_MASK) | (oldCPSR & FIQ_MASK));
return _cpsr;
}
unsigned enableFIQ(void)
{
unsigned _cpsr;
_cpsr = __get_cpsr();
__set_cpsr(_cpsr & ~FIQ_MASK);
return _cpsr;
}

View file

@ -0,0 +1,272 @@
/*
* Defines and Macros for Interrupt-Service-Routines
* collected and partly created by
* Martin Thomas <mthomas@rhrk.uni-kl.de>
*
* Copyright 2005 M. Thomas
* No guarantees, warrantees, or promises, implied or otherwise.
* May be used for hobby or commercial purposes provided copyright
* notice remains intact.
*/
#ifndef interrupt_utils_
#define interrupt_utils_
/*
The following defines are usefull for
interrupt service routine declarations.
*/
/*
RAMFUNC
Attribute which defines a function to be located
in memory section .fastrun and called via "long calls".
See linker-skript and startup-code to see how the
.fastrun-section is handled.
The definition is not only useful for ISRs but since
ISRs should be executed fast the macro is defined in
this header.
*/
#define RAMFUNC __attribute__ ((long_call, section (".fastrun")))
/*
INTFUNC
standard attribute for arm-elf-gcc which marks
a function as ISR (for the VIC). Since gcc seems
to produce wrong code if this attribute is used in
thumb/thumb-interwork the attribute should only be
used for "pure ARM-mode" binaries.
*/
#define INTFUNC __attribute__ ((interrupt("IRQ")))
/*
NACKEDFUNC
gcc will not add any code to a function declared
"nacked". The user has to take care to save registers
and add the needed code for ISR functions. Some
macros for this tasks are provided below.
*/
#define NACKEDFUNC __attribute__((naked))
/******************************************************************************
*
* MACRO Name: ISR_STORE()
*
* Description:
* This MACRO is used upon entry to an ISR with interrupt nesting.
* Should be used together with ISR_ENABLE_NEST(). The MACRO
* performs the following steps:
*
* 1 - Save the non-banked registers r0-r12 and lr onto the IRQ stack.
*
*****************************************************************************/
#define ISR_STORE() asm volatile( \
"STMDB SP!,{R0-R12,LR}\n" )
/******************************************************************************
*
* MACRO Name: ISR_RESTORE()
*
* Description:
* This MACRO is used upon exit from an ISR with interrupt nesting.
* Should be used together with ISR_DISABLE_NEST(). The MACRO
* performs the following steps:
*
* 1 - Load the non-banked registers r0-r12 and lr from the IRQ stack.
* 2 - Adjusts resume adress
*
*****************************************************************************/
#define ISR_RESTORE() asm volatile( \
"LDMIA SP!,{R0-R12,LR}\n" \
"SUBS R15,R14,#0x0004\n" )
/******************************************************************************
*
* MACRO Name: ISR_ENABLE_NEST()
*
* Description:
* This MACRO is used upon entry from an ISR with interrupt nesting.
* Should be used after ISR_STORE.
*
*****************************************************************************/
#define ISR_ENABLE_NEST() asm volatile( \
"MRS LR, SPSR \n" \
"STMFD SP!, {LR} \n" \
"MSR CPSR_c, #0x1f \n" \
"STMFD SP!, {LR} " )
/******************************************************************************
*
* MACRO Name: ISR_DISABLE_NEST()
*
* Description:
* This MACRO is used upon entry from an ISR with interrupt nesting.
* Should be used before ISR_RESTORE.
*
*****************************************************************************/
#define ISR_DISABLE_NEST() asm volatile( \
"LDMFD SP!, {LR} \n" \
"MSR CPSR_c, #0x92 \n" \
"LDMFD SP!, {LR} \n" \
"MSR SPSR_cxsf, LR \n" )
/*
* The following marcos are from the file "armVIC.h" by:
*
* Copyright 2004, R O SoftWare
* No guarantees, warrantees, or promises, implied or otherwise.
* May be used for hobby or commercial purposes provided copyright
* notice remains intact.
*
*/
/******************************************************************************
*
* MACRO Name: ISR_ENTRY()
*
* Description:
* This MACRO is used upon entry to an ISR. The current version of
* the gcc compiler for ARM does not produce correct code for
* interrupt routines to operate properly with THUMB code. The MACRO
* performs the following steps:
*
* 1 - Adjust address at which execution should resume after servicing
* ISR to compensate for IRQ entry
* 2 - Save the non-banked registers r0-r12 and lr onto the IRQ stack.
* 3 - Get the status of the interrupted program is in SPSR.
* 4 - Push it onto the IRQ stack as well.
*
*****************************************************************************/
#define ISR_ENTRY() asm volatile(" sub lr, lr,#4\n" \
" stmfd sp!,{r0-r12,lr}\n" \
" mrs r1, spsr\n" \
" stmfd sp!,{r1}")
/******************************************************************************
*
* MACRO Name: ISR_EXIT()
*
* Description:
* This MACRO is used to exit an ISR. The current version of the gcc
* compiler for ARM does not produce correct code for interrupt
* routines to operate properly with THUMB code. The MACRO performs
* the following steps:
*
* 1 - Recover SPSR value from stack
* 2 - and restore its value
* 3 - Pop the return address & the saved general registers from
* the IRQ stack & return
*
*****************************************************************************/
#define ISR_EXIT() asm volatile(" ldmfd sp!,{r1}\n" \
" msr spsr_c,r1\n" \
" ldmfd sp!,{r0-r12,pc}^")
/******************************************************************************
*
* Function Name: disableIRQ()
*
* Description:
* This function sets the IRQ disable bit in the status register
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned disableIRQ(void);
/******************************************************************************
*
* Function Name: enableIRQ()
*
* Description:
* This function clears the IRQ disable bit in the status register
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned enableIRQ(void);
/******************************************************************************
*
* Function Name: restoreIRQ()
*
* Description:
* This function restores the IRQ disable bit in the status register
* to the value contained within passed oldCPSR
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned restoreIRQ(unsigned oldCPSR);
/******************************************************************************
*
* Function Name: disableFIQ()
*
* Description:
* This function sets the FIQ disable bit in the status register
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned disableFIQ(void);
/******************************************************************************
*
* Function Name: enableFIQ()
*
* Description:
* This function clears the FIQ disable bit in the status register
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned enableFIQ(void);
/******************************************************************************
*
* Function Name: restoreFIQ()
*
* Description:
* This function restores the FIQ disable bit in the status register
* to the value contained within passed oldCPSR
*
* Calling Sequence:
* void
*
* Returns:
* previous value of CPSR
*
*****************************************************************************/
unsigned restoreFIQ(unsigned oldCPSR);
#endif

15
cpu/at91sam7s/io.h Normal file
View file

@ -0,0 +1,15 @@
#ifndef __IO_H__7UTLUP9AG6__
#define __IO_H__7UTLUP9AG6__
#include <AT91SAM7S64.h>
#ifndef BV
#define BV(x) (1<<(x))
#endif
int splhigh(void);
void splx(int saved);
#endif /* __IO_H__7UTLUP9AG6__ */

View file

@ -0,0 +1,8 @@
SECTIONS
{
.text :
{
*(.text)
*(.rodata.* .rodata)
}
}

View file

@ -0,0 +1,98 @@
#include <debug-uart.h>
#include <sys/stat.h>
#include <errno.h>
int
_open(const char *name, int flags, int mode) {
errno = ENOENT;
return -1;
}
int
_close(int file)
{
if (file == 1 || file == 2) {
dbg_drain();
return 0;
}
errno = EBADF;
return -1;
}
int
isatty(int file)
{
if (file >= 0 && file <= 2) return 1;
return 0;
}
int
_read(int file, char *ptr, int len){
return 0;
}
int
_write(int file, const char *ptr, int len){
int sent = -1;
if (file == 1 || file == 2) {
sent = dbg_send_bytes((const unsigned char*)ptr, len);
}
return sent;
}
int
_lseek(int file, int ptr, int dir){
return 0;
}
int
_fstat(int file, struct stat *st) {
if (file >= 0 && file <= 2) {
st->st_mode = S_IFCHR;
return 0;
}
errno = EBADF;
return -1;
}
int
_stat(char *file, struct stat *st) {
errno = ENOENT;
return -1;
}
caddr_t
_sbrk(int incr)
{
extern char __heap_start__; /* Defined by the linker */
extern char __heap_end__; /* Defined by the linker */
static char *heap_end;
char *prev_heap_end;
if (heap_end == 0) {
heap_end = &__heap_start__;
}
prev_heap_end = heap_end;
if (heap_end + incr > &__heap_end__) {
_write (2, "Heap full\n", 10);
errno = ENOMEM;
return (caddr_t)-1;
}
heap_end += incr;
return (caddr_t) prev_heap_end;
}
int
fsync(int fd)
{
if (fd == 1 || fd == 2) {
dbg_drain();
return 0;
}
if (fd == 0) return 0;
errno = EBADF;
return -1;
}

View file

@ -0,0 +1 @@
arm7_9 force_hw_bkpts enable

View file

@ -0,0 +1,30 @@
#daemon configuration
telnet_port 4444
gdb_port 3333
#interface
interface parport
parport_port 0
parport_cable wiggler
jtag_speed 0
#use combined on interfaces or targets that can't set TRST/SRST separately
reset_config srst_only
#jtag scan chain
#format L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE)
jtag_device 4 0x1 0xf 0xe
#target configuration
daemon_startup reset
#target <type> <startup mode>
#target arm7tdmi <reset mode> <chainpos> <endianness> <variant>
target arm7tdmi little run_and_init 0 arm7tdmi_r4
#target_script 0 reset h2294_init.script
target_script 0 reset AT91SAM7x_init.script
run_and_halt_time 0 30
working_area 0 0x40000000 0x4000 nobackup
#flash configuration
#flash bank lpc2000 0x0 0x40000 0 0 lpc2000_v1 0 14765 calc_checksum
#flash bank cfi 0x80000000 0x400000 2 2 0
flash bank at91sam7 0 0 0 0 0

View file

@ -0,0 +1,30 @@
#daemon configuration
telnet_port 4444
gdb_port 3333
#interface
interface parport
parport_port 0
parport_cable wiggler
jtag_speed 0
#use combined on interfaces or targets that can't set TRST/SRST separately
reset_config srst_only
#jtag scan chain
#format L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE)
jtag_device 4 0x1 0xf 0xe
#target configuration
daemon_startup reset
#target <type> <startup mode>
#target arm7tdmi <reset mode> <chainpos> <endianness> <variant>
target arm7tdmi little run_and_init 0 arm7tdmi_r4
#target_script 0 reset h2294_init.script
target_script 0 reset openocd_flash
run_and_halt_time 0 30
working_area 0 0x40000000 0x4000 nobackup
#flash configuration
#flash bank lpc2000 0x0 0x40000 0 0 lpc2000_v1 0 14765 calc_checksum
#flash bank cfi 0x80000000 0x400000 2 2 0
flash bank at91sam7 0 0 0 0 0

View file

@ -0,0 +1,30 @@
#daemon configuration
telnet_port 4444
gdb_port 3333
#interface
interface parport
parport_port 0
parport_cable wiggler
jtag_speed 0
#use combined on interfaces or targets that can't set TRST/SRST separately
reset_config srst_only
#jtag scan chain
#format L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE)
jtag_device 4 0x1 0xf 0xe
#target configuration
daemon_startup reset
#target <type> <startup mode>
#target arm7tdmi <reset mode> <chainpos> <endianness> <variant>
target arm7tdmi little run_and_init 0 arm7tdmi_r4
#target_script 0 reset h2294_init.script
target_script 0 reset openocd_reset
run_and_halt_time 0 30
working_area 0 0x40000000 0x4000 nobackup
#flash configuration
#flash bank lpc2000 0x0 0x40000 0 0 lpc2000_v1 0 14765 calc_checksum
#flash bank cfi 0x80000000 0x400000 2 2 0
flash bank at91sam7 0 0 0 0 0

View file

@ -0,0 +1,10 @@
poll
mww 0xffffff64 0x5a000004
sleep 250
mww 0xffffff64 0x5a002004
sleep 250
flash probe 0
flash write 0 /tmp/openocd_write.bin 0x0
reset run
sleep 500
shutdown

View file

@ -0,0 +1,4 @@
poll
reset run
sleep 500
shutdown

View file

@ -0,0 +1,22 @@
volatile unsigned int pit_count = 0;
static void NACKEDFUNC ATTR system_int (void) { /* System Interrupt Handler */
ISR_ENTRY();
if (*AT91C_PITC_PISR & AT91C_PITC_PITS) { /* Check PIT Interrupt */
pit_count++;
/*
if ((pit_count % 100) == 0) {
unsigned int led_state = (pit_count % 300) / 100;
*AT91C_PIOA_ODSR = ~(1<<led_state);
}
*/
*AT91C_AIC_EOICR = *AT91C_PITC_PIVR; /* Ack & End of Interrupt */
} else {
*AT91C_AIC_EOICR = 0; /* End of Interrupt */
}
ISR_EXIT();
}

View file

@ -0,0 +1,100 @@
#include <sys-interrupt.h>
#include <interrupt-utils.h>
#include <AT91SAM7S64.h>
#define ATTR
#ifndef NULL
#define NULL 0
#endif
static SystemInterruptHandler *handlers = NULL;
static void
system_int_safe (void) __attribute__((noinline));
static void
system_int_safe (void)
{
SystemInterruptHandler *h;
h = handlers;
while (h) {
if (h->handler()) break;
h = h->next;
}
}
static void NACKEDFUNC ATTR
system_int (void) /* System Interrupt Handler */
{
ISR_ENTRY();
system_int_safe();
*AT91C_AIC_EOICR = 0; /* End of Interrupt */
ISR_EXIT();
}
static unsigned int enabled = 0; /* Number of times the system
interrupt has been enabled */
#define DIS_INT *AT91C_AIC_IDCR = (1 << AT91C_ID_SYS)
#define EN_INT if (enabled > 0) *AT91C_AIC_IECR = (1 << AT91C_ID_SYS)
void
sys_interrupt_enable()
{
if (enabled++ == 0) {
/* Level trigged at priority 5 */
AT91C_AIC_SMR[AT91C_ID_SYS] = AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL | 5;
/* Interrupt vector */
AT91C_AIC_SVR[AT91C_ID_SYS] = (unsigned long) system_int;
/* Enable */
EN_INT;
}
}
void
sys_interrupt_disable()
{
if (--enabled == 0) {
DIS_INT;
}
}
void
sys_interrupt_append_handler(SystemInterruptHandler *handler)
{
SystemInterruptHandler **h = &handlers;
while(*h) {
h = &(*h)->next;
}
DIS_INT;
*h = handler;
handler->next = NULL;
EN_INT;
}
void
sys_interrupt_prepend_handler(SystemInterruptHandler *handler)
{
DIS_INT;
handler->next = handlers;
handlers = handler;
EN_INT;
}
void
sys_interrupt_remove_handler(SystemInterruptHandler *handler)
{
SystemInterruptHandler **h = &handlers;
while(*h) {
if (*h == handler) {
DIS_INT;
*h = handler->next;
EN_INT;
break;
}
h = &(*h)->next;
}
}

View file

@ -0,0 +1,31 @@
#ifndef __SYS_INTERRUPT_H__QIHZ66NP8K__
#define __SYS_INTERRUPT_H__QIHZ66NP8K__
/* Returns true if it handled an activbe interrupt */
typedef int (*SystemInterruptFunc)();
typedef struct _SystemInterruptHandler SystemInterruptHandler;
struct _SystemInterruptHandler
{
SystemInterruptHandler *next;
SystemInterruptFunc handler;
};
void
sys_interrupt_enable();
void
sys_interrupt_disable();
void
sys_interrupt_append_handler(SystemInterruptHandler *handler);
void
sys_interrupt_prepend_handler(SystemInterruptHandler *handler);
void
sys_interrupt_remove_handler(SystemInterruptHandler *handler);
#endif /* __SYS_INTERRUPT_H__QIHZ66NP8K__ */

6
cpu/at91sam7s/uip-log.c Normal file
View file

@ -0,0 +1,6 @@
#include <stdio.h>
void uip_log(char *msg)
{
printf("uip: %s\n", msg);
}