Add initial ADuCRF101 CPU support

This commit is contained in:
Jim Paris 2014-06-21 22:35:42 -04:00
parent 2be02cd269
commit baa6058839
12 changed files with 1003 additions and 0 deletions

View File

@ -0,0 +1,105 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
ENTRY(Reset_Handler)
MEMORY
{
flash (rx) : org = 0x00000000, len = 128k
ram (rwx) : org = 0x20000000, len = 16k
}
SECTIONS
{
.vectors : {
__vectors_start = .;
KEEP(*(.vectors))
. = ALIGN(4);
} >flash
.text : {
. = ALIGN(4);
*(.text)
*(.text.*)
etext = .;
} >flash
.ARM.ex : {
*(.ARM.extab* .gnu.linkonce.armextab.*)
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} >flash
.rodata : {
. = ALIGN(4);
*(.rodata)
*(.rodata.*)
. = ALIGN(4);
__rodata_end = .;
} >flash
.data : {
/* Initialized data is placed in flash, and will get
copied to RAM by crt0.S */
. = ALIGN(4);
__data_flash_start = LOADADDR(.data);
__data_start = .;
*(.data)
*(.data.*)
/* Code that goes into RAM also ends up here, and
gets copied along with the data section. */
*(.ramtext*)
__data_end = .;
edata = .;
} > ram AT > flash
.bss : {
/* Stack is in BSS */
. = ALIGN(8);
__bss_start = .;
*(.bss.stack)
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
__bss_end = .;
end = .;
} > ram
}

View File

@ -0,0 +1,184 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __STACK_SIZE
#define __STACK_SIZE 1024
#endif
.equ SCB_VTOR, 0xE000ED08
/* Stack */
.section .bss.stack
stack_start:
.space __STACK_SIZE, 0
stack_end:
.global stack_end
/* Vector table */
.macro handler name
.long \name\()
.weak \name\()
.set \name\(), unhandled_vector
.endm
.macro handler_reserved
.long 0
.endm
.section .vectors, "a", %progbits
vectors:
.long stack_end
.long Reset_Handler
/* Cortex-M3 core interrupts */
handler NMI_Handler
handler HardFault_Handler
handler MemManage_Handler
handler BusFault_Handler
handler UsageFault_Handler
handler_reserved
handler_reserved
handler_reserved
handler_reserved
handler SVC_Handler
handler DebugMon_Handler
handler_reserved
handler PendSV_Handler
handler SysTick_Handler
/* ADuCRF101 external interrupts */
handler WakeUp_Int_Handler
handler Ext_Int0_Handler
handler Ext_Int1_Handler
handler Ext_Int2_Handler
handler Ext_Int3_Handler
handler Ext_Int4_Handler
handler Ext_Int5_Handler
handler Ext_Int6_Handler
handler Ext_Int7_Handler
handler Ext_Int8_Handler
handler WDog_Tmr_Int_Handler
handler_reserved
handler GP_Tmr0_Int_Handler
handler GP_Tmr1_Int_Handler
handler ADC0_Int_Handler
handler Flsh_Int_Handler
handler UART_Int_Handler
handler SPI0_Int_Handler
handler SPI1_Int_Handler
handler I2C0_Slave_Int_Handler
handler I2C0_Master_Int_Handler
handler_reserved
handler_reserved
handler DMA_Err_Int_Handler
handler DMA_SPI1_TX_Int_Handler
handler DMA_SPI1_RX_Int_Handler
handler DMA_UART_TX_Int_Handler
handler DMA_UART_RX_Int_Handler
handler DMA_I2C0_STX_Int_Handler
handler DMA_I2C0_SRX_Int_Handler
handler DMA_I2C0_MTX_Int_Handler
handler DMA_I2C0_MRX_Int_Handler
handler_reserved
handler_reserved
handler_reserved
handler DMA_ADC_Int_Handler
handler DMA_SPI0_TX_Int_Handler
handler DMA_SPI0_RX_Int_Handler
handler PWMTrip_Int_Handler
handler PWM0_Int_Handler
handler PWM1_Int_Handler
handler PWM2_Int_Handler
handler PWM3_Int_Handler
/* Reset handler */
.section .text
.syntax unified
.code 16
.global Reset_Handler
.thumb_func
Reset_Handler:
/* Set up some basics, in case we came here from a call
rather than system reset. */
/* Disable interrupts */
cpsid i
/* Privileged mode, main stack, no floating point */
mov r0, #0
msr control, r0
isb
/* Point vector table to the right place */
ldr r0, =__vectors_start
ldr r1, =SCB_VTOR
str r0, [r1]
/* Load initial stack pointer */
ldr r0, =stack_end
mov sp, r0
isb
/* Clear BSS */
mov r0, #0
ldr r1, =__bss_start
ldr r2, =__bss_end
zero_bss_loop:
cmp r1, r2
it lt
strlt r0, [r1], #4
blt zero_bss_loop
/* Copy initialized data from flash to RAM */
ldr r0, =__data_flash_start
ldr r1, =__data_start
ldr r2, =__data_end
copy_data_loop:
ldr r3, [r0], #4
cmp r1, r2
it lt
strlt r3, [r1], #4
blt copy_data_loop
/* We can run C code now */
bl main
/* If main returned, just loop */
b .
/* Handler for otherwise unhandled vectors */
.section .text,"ax",%progbits
.thumb_func
unhandled_vector:
b unhandled_vector

View File

@ -0,0 +1,125 @@
# -*- makefile -*-
# Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted (subject to the limitations in the
# disclaimer below) provided that the following conditions are met:
#
# - Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# - Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the
# distribution.
#
# - Neither the name of Analog Devices, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
# GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
# HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
# WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
# MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
# BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
# WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
# OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
# IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
# Author: Jim Paris <jim.paris@rigado.com>
CONTIKI_CPU = $(CONTIKI)/cpu/arm/aducrf101
CROSS_COMPILE = arm-none-eabi-
CC = $(CROSS_COMPILE)gcc
LD = $(CROSS_COMPILE)gcc
AS = $(CROSS_COMPILE)gcc
AR = $(CROSS_COMPILE)ar
NM = $(CROSS_COMPILE)nm
OBJCOPY = $(CROSS_COMPILE)objcopy
OBJDUMP = $(CROSS_COMPILE)objdump
STRIP = $(CROSS_COMPILE)strip
CFLAGS_OPT ?= -Os
CFLAGS_DEBUG ?= -ggdb3 -fomit-frame-pointer
CFLAGS += $(CFLAGS_OPT) $(CFLAGS_DEBUG)
CFLAGS += -std=gnu99
CFLAGS += -ffreestanding -mcpu=cortex-m3 -mthumb -mno-thumb-interwork
CFLAGS += -ffunction-sections -fdata-sections -fno-common -fno-builtin
CFLAGS += -flto
ifdef WERROR
CFLAGS += -Wall -Werror
# These warnings are triggered by existing Contiki code
CFLAGS += -Wno-error=pointer-sign
CFLAGS += -Wno-error=char-subscripts
CFLAGS += -Wno-error=unused-variable
CFLAGS += -Wno-error=unused-but-set-variable
endif
# UIP code does not follow C aliasing rules
CFLAGS += -fno-strict-aliasing
LDFLAGS = $(CFLAGS)
LDFLAGS += -specs=nosys.specs -nostartfiles
# TODO: When it becomes more commonly available, switch to newlib-nano
# for significant size reduction, by uncommenting this:
# LDFLAGS += -specs=nano.specs
LDFLAGS += -Wl,--gc-sections
LDFLAGS += -Wl,-T$(CONTIKI_CPU)/Common/GCC/ADuCRF101.ld
# Compiler-specific startup code
CONTIKI_CPU_DIRS += Common/GCC
CONTIKI_SOURCEFILES += crt0.S
ifdef SERIAL_ID
CFLAGS += -DSERIAL_ID='$(SERIAL_ID)'
endif
ifdef __STACK_SIZE
CFLAGS += -D__STACK_SIZE=$(__STACK_SIZE)
endif
# HSI internal oscillator by default
CFLAGS += -DF_CPU=16000000
### CPU-dependent directories and source files
CONTIKI_CPU_DIRS += ../common/CMSIS
CONTIKI_CPU_DIRS += .
CONTIKI_SOURCEFILES += slip-arch.c
CONTIKI_CPU_DIRS += dev
CONTIKI_SOURCEFILES += uart.c
CONTIKI_SOURCEFILES += clock.c
CONTIKI_SOURCEFILES += watchdog.c
CONTIKI_CPU_DIRS += Common
CONTIKI_SOURCEFILES += system_ADuCRF101.c
ASFLAGS += -c $(CFLAGS)
ifdef CORE
.PHONY: symbols.c symbols.h
symbols.c symbols.h:
$(NM) -C $(CORE) | grep -v @ | grep -v dll_crt0 | \
awk -f $(CONTIKI)/tools/mknmlist > symbols.c || rm -f symbols.c
else
symbols.c symbols.h:
cp ${CONTIKI}/tools/empty-symbols.c symbols.c
cp ${CONTIKI}/tools/empty-symbols.h symbols.h
endif
contiki-$(TARGET).a: ${addprefix $(OBJECTDIR)/,symbols.o}
%.hex: %
$(OBJCOPY) -O ihex $^ $@

View File

@ -0,0 +1,52 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#ifndef ADUCRF101_CONTIKI_H
#define ADUCRF101_CONTIKI_H
#include <stdint.h>
#include <aducrf101-include.h>
typedef uint32_t clock_time_t;
typedef uint16_t uip_stats_t;
typedef unsigned long rtimer_clock_t;
#define RTIMER_CLOCK_LT(a, b) ((signed long)((a) - (b)) < 0)
rtimer_clock_t rtimer_arch_now(void);
#endif

94
cpu/arm/aducrf101/clock.c Normal file
View File

@ -0,0 +1,94 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#include <aducrf101-contiki.h>
#include <sys/clock.h>
#include <sys/etimer.h>
static volatile clock_time_t current_clock = 0;
static volatile unsigned long current_seconds = 0;
static unsigned int second_countdown = CLOCK_SECOND;
void
SysTick_handler(void) __attribute__ ((interrupt));
void
SysTick_Handler(void)
{
current_clock++;
if(etimer_pending()) {
etimer_request_poll();
}
if(--second_countdown == 0) {
current_seconds++;
second_countdown = CLOCK_SECOND;
}
}
/*---------------------------------------------------------------------------*/
void
clock_init()
{
SysTick_Config(F_CPU / CLOCK_SECOND);
}
/*---------------------------------------------------------------------------*/
clock_time_t
clock_time(void)
{
return current_clock;
}
/*---------------------------------------------------------------------------*/
unsigned long
clock_seconds(void)
{
return current_seconds;
}
/*---------------------------------------------------------------------------*/
void
clock_delay_usec(uint16_t usec)
{
/* Delay by watching the SysTick value change. */
int32_t remaining = (int32_t)usec * F_CPU / 1000000;
int32_t old = SysTick->VAL;
while(remaining > 0) {
int32_t new = SysTick->VAL;
if(new > old) { /* wraparound */
old += SysTick->LOAD;
}
remaining -= (old - new);
old = new;
}
}

View File

@ -0,0 +1,116 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#include <unistd.h>
#include <aducrf101-include.h>
static int (*uart_input_handler)(unsigned char c);
static int stdout_enabled;
void
uart_init(int baud)
{
/* P1.0 is UARTRXD, P1.1 is UARTTXD */
pADI_GP1->GPCON &= ~(GP1CON_CON0_MSK | GP1CON_CON1_MSK);
pADI_GP1->GPCON |= GP1CON_CON0_UART0RXD | GP1CON_CON1_UART0TXD;
/* Set P1.1 as output */
GP1OEN_OEN1_BBA = 1;
/* Set baudrate */
int div = (F_CPU / 32) / baud;
pADI_UART->COMDIV = div;
pADI_UART->COMFBR = 0x8800 | ((((64 * F_CPU) / div) / baud) - 2048);
pADI_UART->COMIEN = 0;
pADI_UART->COMLCR = 3;
/* Set up RX IRQ */
pADI_UART->COMIEN = COMIEN_ERBFI_EN;
NVIC_EnableIRQ(UART_IRQn);
__enable_irq();
uart_input_handler = NULL;
stdout_enabled = 1;
}
/*---------------------------------------------------------------------------*/
void
uart_put(unsigned char x)
{
while(!(pADI_UART->COMLSR & COMLSR_THRE))
continue;
pADI_UART->COMTX = x;
}
/*---------------------------------------------------------------------------*/
void
UART_Int_Handler(void)
{
if(pADI_UART->COMIIR & COMIIR_STA_RXBUFFULL) {
unsigned char x = pADI_UART->COMRX;
if(uart_input_handler) {
uart_input_handler(x);
}
}
}
/*---------------------------------------------------------------------------*/
void
uart_set_input(int (*input)(unsigned char c))
{
uart_input_handler = input;
}
void
uart_enable_stdout(int enabled)
{
stdout_enabled = enabled;
}
/*---------------------------------------------------------------------------*/
/* Connect newlib's _write function to the UART. */
int
_write(int fd, const void *buf, size_t len)
{
if(stdout_enabled == 0) {
return -1;
}
if(fd == STDOUT_FILENO || fd == STDERR_FILENO) {
int n = len;
const unsigned char *p = buf;
while(n--)
uart_put(*p++);
return len;
}
return -1;
}

View File

@ -0,0 +1,47 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#ifndef UART_H
#define UART_H
void uart_init(int baud);
void uart_put(unsigned char x);
void uart_set_input(int (*input)(unsigned char c));
void uart_enable_stdout(int enabled);
#endif

View File

@ -0,0 +1,67 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#include <aducrf101-contiki.h>
#include <watchdog.h>
void
watchdog_init(void)
{
/* Start disabled. */
T3CON_ENABLE_BBA = 0;
}
/*---------------------------------------------------------------------------*/
void
watchdog_start(void)
{
/* 32 second timeout. This also locks the watchdog configuration. */
pADI_WDT->T3CON = 0x00E9;
pADI_WDT->T3LD = 0x1000;
pADI_WDT->T3VAL = 0x1000;
}
/*---------------------------------------------------------------------------*/
void
watchdog_stop(void)
{
/* Not possible to stop, once enabled */
}
/*---------------------------------------------------------------------------*/
void
watchdog_periodic(void)
{
pADI_WDT->T3CLRI = 0xcccc;
}

View File

@ -0,0 +1,47 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#ifndef MTARCH_H_
#define MTARCH_H_
/* Multithreading is currently unimplemented for ARM Cortex-M3 */
struct mtarch_thread {
short mt_thread;
};
#endif /* MTARCH_H_ */

View File

@ -0,0 +1,59 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#include "rtimer-arch.h"
void
rtimer_arch_init(void)
{
}
/*---------------------------------------------------------------------------*/
void
rtimer_arch_schedule(rtimer_clock_t t)
{
}
/*---------------------------------------------------------------------------*/
void
rtimer_arch_set(rtimer_clock_t t)
{
}
/*---------------------------------------------------------------------------*/
rtimer_clock_t
rtimer_arch_now(void)
{
return 0;
}

View File

@ -0,0 +1,47 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#ifndef __RTIMER_ARCH_H__
#define __RTIMER_ARCH_H__
#include <stdint.h>
#define RTIMER_ARCH_SECOND (1000)
#include "sys/rtimer.h"
#endif /* __RTIMER_ARCH_H__ */

View File

@ -0,0 +1,60 @@
/**
* Copyright (c) 2014, Analog Devices, Inc. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted (subject to the limitations in the
* disclaimer below) provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the
* distribution.
*
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
* GRANTED BY THIS LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
* HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
* BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
* OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
* IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author Jim Paris <jim.paris@rigado.com>
*/
#include <stdio.h>
#include "contiki.h"
#include "dev/slip.h"
#include "uart.h"
/*---------------------------------------------------------------------------*/
void
slip_arch_writeb(unsigned char c)
{
uart_put(c);
}
/*---------------------------------------------------------------------------*/
/**
* Initalize the RS232 port and the SLIP driver.
*
*/
void
slip_arch_init(unsigned long ubr)
{
uart_set_input(slip_input_byte);
}
/*---------------------------------------------------------------------------*/